Skip to content

Commit 2ca708b

Browse files
Jayasinghe, Oshada (Data61, Pullenvale)Jayasinghe, Oshada (Data61, Pullenvale)
authored andcommitted
Merge pull request #19 in OSHC/syropod_highlevel_controller from feature/namespace_directives to master
* commit '5d7594abb86a9ab19983ea76d2c8e53ae9c1ab5f': Various whitespace changes to fit lines within 120 chars Removed vscode folder Fixed line lengths to 120 characters and aligned inline comments Removed std namespace from standard includes header Removed ros namespace from standard includes header Removed tf2_ros namespace from standard includes header Removed Eigen namespace from standard includes header
2 parents 57f29c9 + 5d7594a commit 2ca708b

15 files changed

+1154
-1068
lines changed

include/syropod_highlevel_controller/admittance_controller.h

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -33,7 +33,7 @@ class AdmittanceController
3333
/// and calls initialisation.
3434
/// @param[in] model Pointer to the robot model class object
3535
/// @param[in] params Pointer to the parameter struct object
36-
AdmittanceController(shared_ptr<Model> model, const Parameters& params);
36+
AdmittanceController(std::shared_ptr<Model> model, const Parameters& params);
3737

3838
/// Iterates through legs in the robot model and updates the tip position offset value for each.
3939
/// The calculation is achieved through the use of a classical Runge-Kutta ODE solver with a force input
@@ -48,7 +48,7 @@ class AdmittanceController
4848
/// adjacent legs.
4949
/// @param[in] leg A pointer to the leg object associated with the stiffness value to be updated
5050
/// @param[in] scale_reference A double ranging from 0.0->1.0 which controls the scaling of the stiffnesses
51-
void updateStiffness(shared_ptr<Leg> leg, const double& scale_reference);
51+
void updateStiffness(std::shared_ptr<Leg> leg, const double& scale_reference);
5252

5353
/// Scales virtual stiffness of swinging leg and adjacent legs according to the walk cycle of the walk controller.
5454
/// The percentage vertical position difference of the swinging leg tip from it's default position is used as a
@@ -58,11 +58,11 @@ class AdmittanceController
5858
/// load stiffness value applied to the two adjacent legs. The reseting and addition of stiffness allows overlapping
5959
/// step cycles to JOINTLY add stiffness to simultaneously adjacent legs.
6060
/// @param[in] walker A pointer to the walk controller
61-
void updateStiffness(shared_ptr<WalkController> walker);
61+
void updateStiffness(std::shared_ptr<WalkController> walker);
6262

6363
private:
64-
shared_ptr<Model> model_; ///< Pointer to the robot model object
65-
const Parameters& params_; ///< Pointer to parameter data structure for storing parameter variables
64+
std::shared_ptr<Model> model_; ///< Pointer to the robot model object
65+
const Parameters& params_; ///< Pointer to parameter data structure for storing parameter variables
6666

6767
public:
6868
EIGEN_MAKE_ALIGNED_OPERATOR_NEW

include/syropod_highlevel_controller/debug_visualiser.h

Lines changed: 13 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -32,59 +32,59 @@ class DebugVisualiser
3232
/// Publishes visualisation markers which represent the robot model for display in RVIZ. Consists of line segments.
3333
/// linking the origin points of each joint and tip of each leg.
3434
/// @param[in] model A pointer to the robot model object
35-
void generateRobotModel(shared_ptr<Model> model);
35+
void generateRobotModel(std::shared_ptr<Model> model);
3636

3737
/// Publishes visualisation markers which represent the estimated walking plane.
3838
/// @param[in] walk_plane A Vector representing the walk plane
3939
/// @param[in] walk_plane_normal A Vector of the normal to the walk plane
40-
void generateWalkPlane(const Vector3d& walk_plane, const Vector3d& walk_plane_normal);
40+
void generateWalkPlane(const Eigen::Vector3d& walk_plane, const Eigen::Vector3d& walk_plane_normal);
4141

4242
/// Publishes visualisation markers which represent the trajectory of the tip of the input leg.
4343
/// @param[in] leg A pointer to the leg associated with the tip trajectory that is to be published
44-
void generateTipTrajectory(shared_ptr<Leg> leg);
44+
void generateTipTrajectory(std::shared_ptr<Leg> leg);
4545

4646
/// Publishes visualisation markers which represent an estimate of the terrain being traversed.
4747
/// @param[in] model A pointer to the robot model object
48-
void generateTerrainEstimate(shared_ptr<Model> model);
48+
void generateTerrainEstimate(std::shared_ptr<Model> model);
4949

5050
/// Publishes visualisation markers which represent the control nodes of the three bezier curves used to control tip.
5151
/// trajectory of the input leg.
5252
/// @param[in] leg A pointer to the leg associated with the tip trajectory that is to be published
53-
void generateBezierCurves(shared_ptr<Leg> leg);
53+
void generateBezierCurves(std::shared_ptr<Leg> leg);
5454

5555
/// Publishes visualisation markers which represent the default tip position of the leg.
5656
/// @param[in] leg A pointer to a leg of the robot model object
57-
void generateDefaultTipPositions(shared_ptr<Leg> leg);
57+
void generateDefaultTipPositions(std::shared_ptr<Leg> leg);
5858

5959
/// Publises visualisation markers which represent the target tip position of the leg.
6060
/// @param[in] leg A pointer to a leg of the robot model object
61-
void generateTargetTipPositions(shared_ptr<Leg> leg);
61+
void generateTargetTipPositions(std::shared_ptr<Leg> leg);
6262

6363
/// Publishes visualisation markers which represent the 2D walkspace for each leg.
6464
/// @param[in] leg A pointer to a leg of the robot model object
6565
/// @param[in] walkspace A map of walkspace radii for a range of bearings to be visualised
66-
void generateWalkspace(shared_ptr<Leg> leg, const LimitMap& walkspace);
66+
void generateWalkspace(std::shared_ptr<Leg> leg, const LimitMap& walkspace);
6767

6868
/// Publishes visualisation markers which represent the 3D workspace for each leg.
6969
/// @param[in] leg A pointer to a leg of the robot model object
7070
/// @param[in] body_clearance The vertical offset of the body above the walk plane
71-
void generateWorkspace(shared_ptr<Leg> leg, const double& body_clearance);
71+
void generateWorkspace(std::shared_ptr<Leg> leg, const double& body_clearance);
7272

7373
/// Publishes visualisation markers which represent requested stride vector for each leg.
7474
/// @param[in] leg A pointer to the leg associated with the tip trajectory that is to be published
75-
void generateStride(shared_ptr<Leg> leg);
75+
void generateStride(std::shared_ptr<Leg> leg);
7676

7777
/// Publishes visualisation markers which represent the estimated tip force vector for input leg.
7878
/// @param[in] leg A pointer to the leg associated with the tip trajectory that is to be published
79-
void generateTipForce(shared_ptr<Leg> leg);
79+
void generateTipForce(std::shared_ptr<Leg> leg);
8080

8181
/// Publishes visualisation markers which represent the estimated percentage of max torque in each joint.
8282
/// @param[in] leg A pointer to the leg associated with the tip trajectory that is to be published
83-
void generateJointTorques(shared_ptr<Leg> leg);
83+
void generateJointTorques(std::shared_ptr<Leg> leg);
8484

8585
/// Publishes visualisation markers which represent the estimate of the gravitational acceleration vector.
8686
/// @param[in] gravity_estimate An estimate of the gravitational acceleration vector
87-
void generateGravity(const Vector3d& gravity_estimate);
87+
void generateGravity(const Eigen::Vector3d& gravity_estimate);
8888

8989
private:
9090
ros::Publisher robot_model_publisher_; ///< Publisher for topic "/shc/visualisation/robot_model"

0 commit comments

Comments
 (0)