Skip to content

Commit 74eb61c

Browse files
committed
Changed pose to cmd_pose to show command intent.
1 parent 11530f3 commit 74eb61c

File tree

1 file changed

+6
-6
lines changed

1 file changed

+6
-6
lines changed

src/stageros.cpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -62,7 +62,7 @@
6262
#define BASE_SCAN "base_scan"
6363
#define BASE_POSE_GROUND_TRUTH "base_pose_ground_truth"
6464
#define CMD_VEL "cmd_vel"
65-
#define POSE "pose"
65+
#define CMD_POSE "cmd_pose"
6666

6767
// Our node
6868
class StageNode
@@ -98,7 +98,7 @@ class StageNode
9898
std::vector<ros::Publisher> laser_pubs; //multiple lasers
9999

100100
ros::Subscriber cmdvel_sub; //one cmd_vel subscriber
101-
ros::Subscriber pose_sub; //one pos subscriber
101+
ros::Subscriber cmdpose_sub; //one pos subscriber
102102
};
103103

104104
std::vector<StageRobot const *> robotmodels_;
@@ -165,7 +165,7 @@ class StageNode
165165
void cmdvelReceived(int idx, const boost::shared_ptr<geometry_msgs::Twist const>& msg);
166166

167167
// Message callback for a Pose2D message, which sets pose.
168-
void poseReceived(int idx, const boost::shared_ptr<geometry_msgs::Pose2D const>& msg);
168+
void cmdposeReceived(int idx, const boost::shared_ptr<geometry_msgs::Pose2D const>& msg);
169169

170170
// Service callback for soft reset
171171
bool cb_reset_srv(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response);
@@ -273,7 +273,7 @@ StageNode::cmdvelReceived(int idx, const boost::shared_ptr<geometry_msgs::Twist
273273
}
274274

275275
void
276-
StageNode::poseReceived(int idx, const boost::shared_ptr<geometry_msgs::Pose2D const>& msg)
276+
StageNode::cmdposeReceived(int idx, const boost::shared_ptr<geometry_msgs::Pose2D const>& msg)
277277
{
278278
boost::mutex::scoped_lock lock(msg_lock);
279279
Stg::Pose pose;
@@ -372,7 +372,7 @@ StageNode::SubscribeModels()
372372
new_robot->odom_pub = n_.advertise<nav_msgs::Odometry>(mapName(ODOM, r, static_cast<Stg::Model*>(new_robot->positionmodel)), 10);
373373
new_robot->ground_truth_pub = n_.advertise<nav_msgs::Odometry>(mapName(BASE_POSE_GROUND_TRUTH, r, static_cast<Stg::Model*>(new_robot->positionmodel)), 10);
374374
new_robot->cmdvel_sub = n_.subscribe<geometry_msgs::Twist>(mapName(CMD_VEL, r, static_cast<Stg::Model*>(new_robot->positionmodel)), 10, boost::bind(&StageNode::cmdvelReceived, this, r, _1));
375-
new_robot->pose_sub = n_.subscribe<geometry_msgs::Pose2D>(mapName(POSE, r, static_cast<Stg::Model*>(new_robot->positionmodel)), 10, boost::bind(&StageNode::poseReceived, this, r, _1));
375+
new_robot->cmdpose_sub = n_.subscribe<geometry_msgs::Pose2D>(mapName(CMD_POSE, r, static_cast<Stg::Model*>(new_robot->positionmodel)), 10, boost::bind(&StageNode::cmdposeReceived, this, r, _1));
376376

377377
for (size_t s = 0; s < new_robot->lasermodels.size(); ++s)
378378
{
@@ -753,7 +753,7 @@ StageNode::WorldCallback()
753753
int
754754
main(int argc, char** argv)
755755
{
756-
ROS_INFO_STREAM("Custom stage_ros by MAK.");
756+
ROS_INFO_STREAM("Command robot pose programmatically by publishing a geometry_msgs/Pose2D to /pose (single robot) or /robot_#/pose (multiple robots). -MAK");
757757

758758
if( argc < 2 )
759759
{

0 commit comments

Comments
 (0)