Skip to content

Commit

Permalink
Patch applied to support teleporting of stage object. Send it a new p…
Browse files Browse the repository at this point in the history
…osition on cmd_pose, and it will move there. Patch courtesy of ros-simulation/stage_ros#39
  • Loading branch information
Kyle committed Feb 27, 2017
1 parent a658fb9 commit 8c627bf
Showing 1 changed file with 21 additions and 3 deletions.
24 changes: 21 additions & 3 deletions arc_stage/src/stageros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,7 @@
#include <nav_msgs/Odometry.h>
#include <geometry_msgs/Twist.h>
#include <rosgraph_msgs/Clock.h>
#include <geometry_msgs/Pose2D.h>

#include <std_srvs/Empty.h>

Expand All @@ -72,6 +73,7 @@
#define BASE_MARKER_DETECTION "base_marker_detection"
#define BASE_POSE_GROUND_TRUTH "base_pose_ground_truth"
#define CMD_VEL "cmd_vel"
#define CMD_POSE "cmd_pose"
#define NUM_DETECTORS 5
static char * detectors[] = {"detector", "robot_detector", "victim_detector", "marker_detector", "debris_detector"};

Expand Down Expand Up @@ -120,6 +122,7 @@ class StageNode
std::vector<ros::Publisher> fiducial_pubs; //multiple fiducials

ros::Subscriber cmdvel_sub; //one cmd_vel subscriber
ros::Subscriber cmdpose_sub; //one pos subscriber

VelocityCmdsDiffDrive cmdsDes;
};
Expand Down Expand Up @@ -197,7 +200,10 @@ class StageNode

// Message callback for a MsgBaseVel message, which set velocities.
void cmdvelReceived(int idx, const boost::shared_ptr<geometry_msgs::Twist const>& msg);


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

void cmdvelReceivedConstrainedDiffDrive(int idx, const boost::shared_ptr<geometry_msgs::Twist const>& msg);

// Service callback for soft reset
Expand Down Expand Up @@ -356,6 +362,18 @@ StageNode::ghfunc(Stg::Model* mod, StageNode* node)



void
StageNode::cmdposeReceived(int idx, const boost::shared_ptr<geometry_msgs::Pose2D const>& msg)
{
boost::mutex::scoped_lock lock(msg_lock);
Stg::Pose pose;
pose.x = msg->x;
pose.y = msg->y;
pose.z =0;
pose.a = msg->theta;
this->positionmodels[idx]->SetPose(pose);
}

bool
StageNode::cb_reset_srv(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response)
{
Expand Down Expand Up @@ -488,6 +506,8 @@ StageNode::SubscribeModels()

new_robot->odom_pub = n_.advertise<nav_msgs::Odometry>(mapName(ODOM, r, static_cast<Stg::Model*>(new_robot->positionmodel)), 10);
new_robot->ground_truth_pub = n_.advertise<nav_msgs::Odometry>(mapName(BASE_POSE_GROUND_TRUTH, r, static_cast<Stg::Model*>(new_robot->positionmodel)), 10);
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));

if(!config_.constrainedDiffDrive) {
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));
} else {
Expand Down Expand Up @@ -624,8 +644,6 @@ StageNode::WorldCallback()
this->positionmodels[i]->SetSpeed(vAns, 0, wAns);
}
}



this->sim_time.fromSec(world->SimTimeNow() / 1e6);
// We're not allowed to publish clock==0, because it used as a special
Expand Down

0 comments on commit 8c627bf

Please sign in to comment.