Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Provide ability to programmatically change the pose of a robot. #39

Open
wants to merge 6 commits into
base: lunar-devel
Choose a base branch
from
Open
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
19 changes: 19 additions & 0 deletions src/stageros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,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 @@ -62,6 +63,7 @@
#define BASE_SCAN "base_scan"
#define BASE_POSE_GROUND_TRUTH "base_pose_ground_truth"
#define CMD_VEL "cmd_vel"
#define CMD_POSE "cmd_pose"

// Our node
class StageNode
Expand Down Expand Up @@ -97,6 +99,7 @@ class StageNode
std::vector<ros::Publisher> laser_pubs; //multiple lasers

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

std::vector<StageRobot const *> robotmodels_;
Expand Down Expand Up @@ -162,6 +165,9 @@ 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);

// Service callback for soft reset
bool cb_reset_srv(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response);

Expand Down Expand Up @@ -271,6 +277,18 @@ StageNode::cmdvelReceived(int idx, const boost::shared_ptr<geometry_msgs::Twist
this->base_last_cmd = this->sim_time;
}

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);
}

StageNode::StageNode(int argc, char** argv, bool gui, const char* fname, bool use_model_names)
{
this->use_model_names = use_model_names;
Expand Down Expand Up @@ -363,6 +381,7 @@ 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->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));
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));

for (size_t s = 0; s < new_robot->lasermodels.size(); ++s)
{
Expand Down