Skip to content

Commit 2e9f7a4

Browse files
Lu, Bethany(Data61, Pullenvale)Lu, Bethany(Data61, Pullenvale)
authored andcommitted
Standardised naming to primary and secondary within code and readme
1 parent 2252886 commit 2e9f7a4

File tree

4 files changed

+10
-11
lines changed

4 files changed

+10
-11
lines changed

include/syropod_highlevel_controller/state_controller.h

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -291,8 +291,8 @@ class StateController
291291
ros::Subscriber parameter_selection_subscriber_; ///< Subscriber for topic /syropod_remote/parameter_selection
292292
ros::Subscriber parameter_adjustment_subscriber_; ///< Subscriber for topic /syropod_remote/parameter_adjustment
293293

294-
ros::Subscriber primary_tip_pose_subscriber_; ///< Subscriber for topic /syropod_manipulation/AR/Pose
295-
ros::Subscriber secondary_tip_pose_subscriber_; ///< Subscriber for topic /syropod_manipulation/AL/Pose
294+
ros::Subscriber primary_tip_pose_subscriber_; ///< Subscriber for topic /syropod_manipulation/primary/pose
295+
ros::Subscriber secondary_tip_pose_subscriber_; ///< Subscriber for topic /syropod_manipulation/secondary/pose
296296

297297
ros::Subscriber target_configuration_subscriber_; ///< Subscriber for topic /target_configuration
298298
ros::Subscriber target_body_pose_subscriber_; ///< Subscriber for topic /target_body_pose
@@ -373,8 +373,8 @@ class StateController
373373
LegContainer::iterator leg_it_; ///< Leg iteration member variable used to minimise code
374374
JointContainer::iterator joint_it_; ///< Joint iteration member variable used to minimise code
375375

376-
Pose primary_pose_input_; ///< Input for the desired pose of the leg tip AR
377-
Pose secondary_pose_input_; ///< Input for the desired pose of the leg tip AR
376+
Pose primary_pose_input_; ///< Input for the desired pose of primary leg tip
377+
Pose secondary_pose_input_; ///< Input for the desired pose of secondary the leg tip
378378

379379
public:
380380
EIGEN_MAKE_ALIGNED_OPERATOR_NEW

readme.md

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -100,12 +100,12 @@ For information on parameters see readme in config folder.
100100
### Syropod Manipulation:
101101
* AR Leg Tip Position:
102102
* Description: The desired position of leg AR in Cartesian space.
103-
* Topic: */syropod_manipulation/AR/Pose*
103+
* Topic: */syropod_manipulation/primary/Pose*
104104
* Type: geometry_msgs::Pose
105105

106106
* AL Leg Tip Position:
107107
* Description: The desired position of leg AL in Cartesian space.
108-
* Topic: */syropod_manipulation/AL/Pose*
108+
* Topic: */syropod_manipulation/secondary/Pose*
109109
* Type: geometry_msgs::Pose
110110

111111
### Motor and Sensor Inputs

src/state_controller.cpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -63,10 +63,11 @@ StateController::StateController(void)
6363
&StateController::parameterSelectionCallback, this);
6464
parameter_adjustment_subscriber_ = n.subscribe("syropod_remote/parameter_adjustment", 1,
6565
&StateController::parameterAdjustCallback, this);
66+
6667
// Hexapod Leg Manipulation topic subscriptions
67-
primary_tip_pose_subscriber_ = n.subscribe("/syropod_manipulation/AR/Pose", 1,
68+
primary_tip_pose_subscriber_ = n.subscribe("/syropod_manipulation/primary/pose", 1,
6869
&StateController::primaryTipPoseInputCallback, this);
69-
secondary_tip_pose_subscriber_ = n.subscribe("/syropod_manipulation/AL/Pose", 1,
70+
secondary_tip_pose_subscriber_ = n.subscribe("/syropod_manipulation/secondary/pose", 1,
7071
&StateController::secondaryTipPoseInputCallback, this);
7172

7273
// Planner subscription/publisher

src/walk_controller.cpp

Lines changed: 1 addition & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -734,9 +734,7 @@ void WalkController::updateManual(const int &primary_leg_selection_ID, const Pos
734734
{
735735
if (params_.leg_manipulation_mode.data == "tip_control")
736736
{
737-
738737
// TODO add orientation control
739-
// leg_stepper->setCurrentTipPose(Pose(tip_position_input, tip_rotation_input));
740738
leg_stepper->setCurrentTipPose(Pose(tip_position_input, UNDEFINED_ROTATION));
741739
}
742740
}
@@ -1095,7 +1093,7 @@ void LegStepper::updateTipPosition(void)
10951093
target_tip_pose_.position_ += getProjection(difference, walk_plane_normal_);
10961094
}
10971095
// Shift target toward step surface by defined distance and rely on step surface contact detection (REACTIVE)
1098-
else
1096+
else
10991097
{
11001098
target_tip_pose_.position_ -= walker_->getStepDepth() * Eigen::Vector3d::UnitZ();
11011099
}

0 commit comments

Comments
 (0)