From d2b0a3ad1aae2c5ccb56396b320b33fda03316bd Mon Sep 17 00:00:00 2001 From: Olek Bojda Date: Fri, 28 Sep 2018 14:34:55 +0200 Subject: [PATCH] Adjusted xml files and scripts to use messages from rosaria_msgs package --- safety_master_plugin/package.xml | 6 +++--- safety_master_plugin/scripts/ros_master_wrapper.py | 4 ++-- safety_user_plugin/package.xml | 3 +++ safety_user_plugin/scripts/ros_wrapper.py | 4 ++-- 4 files changed, 10 insertions(+), 7 deletions(-) diff --git a/safety_master_plugin/package.xml b/safety_master_plugin/package.xml index 64b732e..a4f058c 100644 --- a/safety_master_plugin/package.xml +++ b/safety_master_plugin/package.xml @@ -14,20 +14,20 @@ rqt_gui rqt_gui_py std_msgs - safety_user_plugin + rosaria_msgs rospy rqt_gui rqt_gui_py std_msgs - safety_user_plugin + rosaria_msgs rospy rqt_gui rqt_gui_py std_msgs message_runtime - safety_user_plugin + rosaria_msgs diff --git a/safety_master_plugin/scripts/ros_master_wrapper.py b/safety_master_plugin/scripts/ros_master_wrapper.py index 5237364..9fa80be 100644 --- a/safety_master_plugin/scripts/ros_master_wrapper.py +++ b/safety_master_plugin/scripts/ros_master_wrapper.py @@ -3,8 +3,8 @@ import rospy import rospkg from std_msgs.msg import Bool -from safety_user_plugin.msg import RobotInfoMsg -from safety_user_plugin.msg import RestrictionsMsg +from rosaria_msgs.msg import RobotInfoMsg +from rosaria_msgs.msg import RestrictionsMsg from robot_info import RobotInfo from master_restrictions import Restrictions diff --git a/safety_user_plugin/package.xml b/safety_user_plugin/package.xml index d4203e5..ed32ff3 100644 --- a/safety_user_plugin/package.xml +++ b/safety_user_plugin/package.xml @@ -15,18 +15,21 @@ rqt_gui_py std_msgs message_generation + rosaria_msgs rospy rqt_gui rqt_gui_py std_msgs message_generation + rosaria_msgs rospy rqt_gui rqt_gui_py std_msgs message_runtime + rosaria_msgs diff --git a/safety_user_plugin/scripts/ros_wrapper.py b/safety_user_plugin/scripts/ros_wrapper.py index 68f32ff..8e08f33 100644 --- a/safety_user_plugin/scripts/ros_wrapper.py +++ b/safety_user_plugin/scripts/ros_wrapper.py @@ -3,8 +3,8 @@ import rospy import rospkg from std_msgs.msg import Bool -from safety_user_plugin.msg import RobotInfoMsg -from safety_user_plugin.msg import RestrictionsMsg +from rosaria_msgs.msg import RobotInfoMsg +from rosaria_msgs.msg import RestrictionsMsg from robot_info import RobotInfo from restrictions import Restrictions