From f5b16b3e0af49b124bec406854f2c541b63a3c2c Mon Sep 17 00:00:00 2001 From: Matthew Klein Date: Mon, 24 Sep 2018 13:40:03 -0400 Subject: [PATCH] Changed pose to cmd_pose to show command intent --- src/stageros.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/src/stageros.cpp b/src/stageros.cpp index 0047f58..edc5677 100644 --- a/src/stageros.cpp +++ b/src/stageros.cpp @@ -62,7 +62,7 @@ #define BASE_SCAN "base_scan" #define BASE_POSE_GROUND_TRUTH "base_pose_ground_truth" #define CMD_VEL "cmd_vel" -#define POSE "pose" +#define CMD_POSE "cmd_pose" // Our node class StageNode @@ -98,7 +98,7 @@ class StageNode std::vector laser_pubs; //multiple lasers ros::Subscriber cmdvel_sub; //one cmd_vel subscriber - ros::Subscriber pose_sub; //one pos subscriber + ros::Subscriber cmdpose_sub; //one pos subscriber }; std::vector robotmodels_; @@ -165,7 +165,7 @@ class StageNode void cmdvelReceived(int idx, const boost::shared_ptr& msg); // Message callback for a Pose2D message, which sets pose. - void poseReceived(int idx, const boost::shared_ptr& msg); + void cmdposeReceived(int idx, const boost::shared_ptr& msg); // Service callback for soft reset 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& msg) +StageNode::cmdposeReceived(int idx, const boost::shared_ptr& msg) { boost::mutex::scoped_lock lock(msg_lock); Stg::Pose pose; @@ -372,7 +372,7 @@ StageNode::SubscribeModels() new_robot->odom_pub = n_.advertise(mapName(ODOM, r, static_cast(new_robot->positionmodel)), 10); new_robot->ground_truth_pub = n_.advertise(mapName(BASE_POSE_GROUND_TRUTH, r, static_cast(new_robot->positionmodel)), 10); new_robot->cmdvel_sub = n_.subscribe(mapName(CMD_VEL, r, static_cast(new_robot->positionmodel)), 10, boost::bind(&StageNode::cmdvelReceived, this, r, _1)); - new_robot->pose_sub = n_.subscribe(mapName(POSE, r, static_cast(new_robot->positionmodel)), 10, boost::bind(&StageNode::poseReceived, this, r, _1)); + new_robot->cmdpose_sub = n_.subscribe(mapName(CMD_POSE, r, static_cast(new_robot->positionmodel)), 10, boost::bind(&StageNode::cmdposeReceived, this, r, _1)); for (size_t s = 0; s < new_robot->lasermodels.size(); ++s) {