demo 1:句柄为相对命名空间不为空,remap便签可只改变nodehandle句柄相对命名空间名称
注:ros::NodeHandle nh("相对命名空间名称")
#include <ros/ros.h>
#include <turtlesim/Pose.h>
#include <geometry_msgs/Twist.h>
class Mimic
{
public:
Mimic();
private:
void poseCallback(const turtlesim::PoseConstPtr& pose);
ros::Publisher twist_pub_;
ros::Subscriber pose_sub_;
};
Mimic::Mimic()
{
ros::NodeHandle input_nh("input");
ros::NodeHandle output_nh("output");
twist_pub_ = output_nh.advertise<geometry_msgs::Twist>("cmd_vel", 1);
pose_sub_ = input_nh.subscribe<turtlesim::Pose>("pose", 1, &Mimic::poseCallback, this);
}
void Mimic::poseCallback(const turtlesim::PoseConstPtr& pose)
{
geometry_msgs::Twist twist;
twist.angular.z = pose->angular_velocity;
twist.linear.x = pose->linear_velocity;
twist_pub_.publish(twist);
}
int main(int argc, char** argv)
{
ros::init(argc, argv, "turtle_mimic");
Mimic mimic;
ros::spin();
}
<launch>
<group ns="turtlesim1">
<node pkg="turtlesim" name="sim" type="turtlesim_node"/>
</group>
<group ns="turtlesim2">
<node pkg="turtlesim" name="sim" type="turtlesim_node"/>
</group>
<node pkg="turtlesim" name="mimic" type="mimic">
<remap from="input" to="turtlesim1/turtle1"/>
<remap from="output" to="turtlesim2/turtle1"/>
</node>
</launch>
demo 2 :remap便签可只改变话题名称
注:nh.advertise<>("话题名称", ) or nh.subscrebe<>("话题名称", , , )
//move_base.cpp
ros::NodeHandle nh;
...
//for comanding the base
vel_pub_ = nh.advertise<geometry_msgs::Twist>("cmd_vel", 1);
<launch>
<include file="$(find turtlebot_navigation)/launch/includes/velocity_smoother.launch.xml"/>
<arg name="odom_topic" default="odom" />
<arg name="laser_topic" default="scan" />
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
<remap from="cmd_vel" to="navigation_velocity_smoother/raw_cmd_vel"/>
<remap from="odom" to="$(arg odom_topic)"/>
<remap from="scan" to="$(arg laser_topic)"/>
</node>
</launch>