存在安全隐患,比如当前工作空间B优先级更高,意味着当程序调用 turtlesim 时,不会调用工作空间A也不会调用系统内置的 turtlesim,如果工作空间A在实现时有其他功能包依赖于自身的 turtlesim,而按照ROS工作空间覆盖的涉及原则,那么实际执行时将会调用工作空间B的turtlesim,从而导致执行异常,出现安全隐患。
当在 .bashrc 文件中 source 多个工作空间后,可能出现的情况,在 ROS PACKAGE PATH 中只包含两个工作空间,可以删除自定义工作空间的 build 与 devel 目录,重新 catkin_make,然后重新载入 .bashrc 文件,问题解决。
rosrun设置命名空间
运行2次:
rosrun turtlesim turtlesim_node
第一次运行的会被强制关闭,留第二次启动的窗口
rosrun turtlesim turtlesim_node __ns:=/xxx //注:__ns 是2个下划线
rosrun turtlesim turtlesim_node __ns:=/yyy
会成功启动2个窗口
rosrun turtlesim turtlesim_node __name:=/xxx //注:__name 是2个下划线
rosrun turtlesim turtlesim_node __name:=/yyy
rosrun turtlesim turtlesim_node __ns:=/xxx __name:=tn
<!-- 需要启动多个乌龟GUI节点 -->
<launch>
<node pkg = "turtlesim" type = "turtlesim_node" name = "turtlesime" />
<!-- 名称重映射 -->>
<node pkg = "turtlesim" type = "turtlesim_node" name = "t1" />
<!-- 命名空间 -->>
<node pkg = "turtlesim" type = "turtlesim_node" name = "turtlesime" ns = "ergouzi"/>
<!-- 命名空间+名称重映射 -->
<node pkg = "turtlesim" type = "turtlesim_node" name = "t2" ns = "maolvzi" />
</launch>
rostopic list 下,/cmd_vel 没有了
rostopic list 下,/turtle1/cmd_vel 没有了
<!-- 键盘控制乌龟运动 -->
<launch>
<!--将乌龟的话题设置为与键盘控制一致-->
<node pkg = "turtlesim" type = "turtlesim_node" name = "t1" >
<remap from = "/turtle1/cmd_vel" to = "/cmd_vel" />
</node>
<node pkg = "teleop_twist_keyboard" type = "teleop_twist_keyboard.py" name = "key" />
</launch>
#include "ros/ros.h"
#include "std_msgs/String.h"
/*
需求:演示不同类型的话题名称设置
设置话题名称与命名空间
*/
int main(int argc, char *argv[])
{
ros::init(argc,argv,"hello");
ros::NodeHandle nh;
//核心:设置不同类型的话题
//1.全局 ---话题名称需以 / 开头(也可以设置自己的命名空间),这种情况下和节点(命名空间及名称)没有关系
ros::Publisher pub = nh.advertise<std_msgs::String>("/chatter",1000);
ros::Publisher pub = nh.advertise<std_msgs::String>("yyy/chatter",1000);
//2.相对 ---非 / 开头 (将内容后缀到命名空间下面)
// ros::Publisher pub = nh.advertise<std_msgs::String>("chatter",1000);
//3.私有 ---需要创建特定 NodeHandle("~") ,后缀在命名空间/节点下
ros::NodeHandle nh("~"); //前面那个NodeHandle需要被注释掉
ros::Publisher pub = nh.advertise<std_msgs::String>("chatter",1000);
//注意:如果私有的NodeHandle创建的话题以 / 开头(全局话题),生成的话题是全局的非私有
//即全局话题优先级更高一些
while (ros::ok())
{
}
return 0;
}
ros::Publisher pub = nh.advertise<std_msgs::String>("/chatter",1000);
// ros::Publisher pub = nh.advertise<std_msgs::String>("yyy/chatter",1000);
ros::Publisher pub = nh.advertise<std_msgs::String>("chatter",1000);
ros::NodeHandle nh("~"); //前面那个NodeHandle需要被注释掉
ros::Publisher pub = nh.advertise<std_msgs::String>("chatter",1000);
#! /usr/bin/env python
import rospy
from std_msgs.msg import String
if __name__ == "__main__":
rospy.init_node("hello")
"""
需求:实现不同类型的话题设置
"""
# 1.全局
pub = rospy.Publisher("/chatter",String,queue_size=10)
pub = rospy.Publisher("/yy/chatter",String,queue_size=10)
# 2.相对
pub = rospy.Publisher("chatter",String,queue_size=10)
# 3.私有
pub = rospy.Publisher("~chatter",String,queue_size=10)
while not rospy.is_shutdown():
pass
1.全局:
pub = rospy.Publisher("/chatter",String,queue_size=10)
pub = rospy.Publisher("chatter",String,queue_size=10)
pub = rospy.Publisher("~chatter",String,queue_size=10)
<!--设置参数-->
<launch>
<!--格式1:全局-->
<param name = "radius" value = "0.2" />
<node pkg = "turtlesim" type = "turtlesim_node" name = "t1" ns ="xxx">
<!--格式2:私有-->
<param name = "radius" value = "0.08" />
</node>
</launch>
#include "ros/ros.h"
int main(int argc, char *argv[])
{
ros::init(argc,argv,"hello");
ros::NodeHandle nh;
/*
使用 ros::param 来设置参数
*/
//1.全局
ros::param::set("/radiusA",100);
//2.相对
ros::param::set("radiusB",100);
//3.私有
ros::param::set("~radiusC",100);
/*
使用 NodeHandle 来设置参数
*/
//1.全局
nh.setParam("/radius_nh_A",1000);
//2.相对
nh.setParam("radius_nh_B",1000);
//3.私有
ros::NodeHandle nh_private("~");
nh_private.setParam("radius_nh_C",1000);
return 0;
}
①使用 ros::param 来设置参数
//使用 ros::param 来设置参数
*/
//1.全局
ros::param::set("/radiusA",100);
//2.相对
ros::param::set("radiusB",100);
//3.私有
ros::param::set("~radiusC",100);
/*
使用 NodeHandle 来设置参数
*/
//1.全局
nh.setParam("/radius_nh_A",1000);
//2.相对
nh.setParam("radius_nh_B",1000);
//3.私有
ros::NodeHandle nh_private("~");
nh_private.setParam("radius_nh_C",1000);
#! /usr/bin/env python
import rospy
if __name__ == "__main__":
rospy.init_node("hello")
"""
设置不同类型的参数
"""
#全局
rospy.set_param("/radiusA",100)
#相对
rospy.set_param("radiusB",100)
#私有
rospy.set_param("~radiusC",100)