Skip to content

Commit 3b3ff84

Browse files
Update related to namespace (#50)
1 parent 2c4f41e commit 3b3ff84

2 files changed

Lines changed: 29 additions & 29 deletions

File tree

launch/motion_decision.launch

Lines changed: 15 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -36,17 +36,17 @@
3636
<arg name="battery/full_charge_voltage" default="24.0"/>
3737
<arg name="battery/cutoff_voltage" default="20.0"/>
3838
<!-- Published topic -->
39-
<arg name="cmd_vel" default="/cmd_vel"/>
39+
<arg name="cmd_vel" default="cmd_vel"/>
4040
<!-- Subscribed topics -->
41-
<arg name="local_path/cmd_vel" default="/local_path/cmd_vel"/>
42-
<arg name="local_map" default="/local_map"/>
43-
<arg name="odom" default="/odom"/>
44-
<arg name="front_laser/scan" default="/front_laser/scan"/>
45-
<arg name="rear_laser/scan" default="/rear_laser/scan"/>
46-
<arg name="battery_voltage" default="/battery_voltage"/>
41+
<arg name="local_path/cmd_vel" default="local_path/cmd_vel"/>
42+
<arg name="local_map" default="local_map"/>
43+
<arg name="odom" default="odom"/>
44+
<arg name="front_laser/scan" default="front_laser/scan"/>
45+
<arg name="rear_laser/scan" default="rear_laser/scan"/>
46+
<arg name="battery_voltage" default="battery_voltage"/>
4747

4848
<!-- run motion_decision node -->
49-
<node pkg="motion_decision" type="motion_decision" name="motion_decision" ns="$(arg ns)" output="$(arg output)" respawn="true">
49+
<node pkg="motion_decision" type="motion_decision" name="motion_decision" output="$(arg output)" respawn="true">
5050
<!-- MotionDecisionParams -->
5151
<param name="use_rear_laser" value="$(arg use_rear_laser)"/>
5252
<param name="use_360_laser" value="$(arg use_360_laser)"/>
@@ -80,13 +80,13 @@
8080
<param name="battery/full_charge_voltage" value="$(arg battery/full_charge_voltage)"/>
8181
<param name="battery/cutoff_voltage" value="$(arg battery/cutoff_voltage)"/>
8282
<!-- Published topic -->
83-
<remap from="/cmd_vel" to="$(arg cmd_vel)"/>
83+
<remap from="cmd_vel" to="$(arg cmd_vel)"/>
8484
<!-- Subscribed topics -->
85-
<remap from="/local_path/cmd_vel" to="$(arg local_path/cmd_vel)"/>
86-
<remap from="/local_map" to="$(arg local_map)"/>
87-
<remap from="/odom" to="$(arg odom)"/>
88-
<remap from="/front_laser/scan" to="$(arg front_laser/scan)"/>
89-
<remap from="/rear_laser/scan" to="$(arg rear_laser/scan)"/>
90-
<remap from="/battery_voltage" to="$(arg battery_voltage)"/>
85+
<remap from="local_path/cmd_vel" to="$(arg local_path/cmd_vel)"/>
86+
<remap from="local_map" to="$(arg local_map)"/>
87+
<remap from="odom" to="$(arg odom)"/>
88+
<remap from="front_laser/scan" to="$(arg front_laser/scan)"/>
89+
<remap from="rear_laser/scan" to="$(arg rear_laser/scan)"/>
90+
<remap from="battery_voltage" to="$(arg battery_voltage)"/>
9191
</node>
9292
</launch>

src/motion_decision.cpp

Lines changed: 14 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -14,22 +14,22 @@
1414

1515
MotionDecision::MotionDecision(void) : private_nh_("~")
1616
{
17-
intersection_flag_pub_ = nh_.advertise<std_msgs::Bool>("/intersection_flag", 1, true);
18-
cmd_vel_pub_ = nh_.advertise<geometry_msgs::Twist>("/cmd_vel", 1, true);
19-
20-
emergency_stop_flag_sub_ = nh_.subscribe("/emergency_stop", 1, &MotionDecision::emergency_stop_flag_callback, this);
21-
front_laser_sub_ = nh_.subscribe("/front_laser/scan", 1, &MotionDecision::front_laser_callback, this);
22-
joy_sub_ = nh_.subscribe("/joy", 1, &MotionDecision::joy_callback, this);
23-
local_path_cmd_vel_sub_ = nh_.subscribe("/local_path/cmd_vel", 1, &MotionDecision::local_path_cmd_vel_callback, this);
24-
local_map_sub_ = nh_.subscribe("/local_map", 1, &MotionDecision::local_map_callback, this);
25-
odom_sub_ = nh_.subscribe("/odom", 1, &MotionDecision::odom_callback, this);
26-
rear_laser_sub_ = nh_.subscribe("/rear_laser/scan", 1, &MotionDecision::rear_laser_callback, this);
27-
battery_voltage_sub_ = nh_.subscribe("/battery_voltage", 1, &MotionDecision::battery_voltage_callback, this);
28-
footprint_sub_ = nh_.subscribe("/footprint", 1, &MotionDecision::footprint_callback, this);
17+
intersection_flag_pub_ = nh_.advertise<std_msgs::Bool>("intersection_flag", 1, true);
18+
cmd_vel_pub_ = nh_.advertise<geometry_msgs::Twist>("cmd_vel", 1, true);
19+
20+
emergency_stop_flag_sub_ = nh_.subscribe("emergency_stop", 1, &MotionDecision::emergency_stop_flag_callback, this);
21+
front_laser_sub_ = nh_.subscribe("front_laser/scan", 1, &MotionDecision::front_laser_callback, this);
22+
joy_sub_ = nh_.subscribe("joy", 1, &MotionDecision::joy_callback, this);
23+
local_path_cmd_vel_sub_ = nh_.subscribe("local_path/cmd_vel", 1, &MotionDecision::local_path_cmd_vel_callback, this);
24+
local_map_sub_ = nh_.subscribe("local_map", 1, &MotionDecision::local_map_callback, this);
25+
odom_sub_ = nh_.subscribe("odom", 1, &MotionDecision::odom_callback, this);
26+
rear_laser_sub_ = nh_.subscribe("rear_laser/scan", 1, &MotionDecision::rear_laser_callback, this);
27+
battery_voltage_sub_ = nh_.subscribe("battery_voltage", 1, &MotionDecision::battery_voltage_callback, this);
28+
footprint_sub_ = nh_.subscribe("footprint", 1, &MotionDecision::footprint_callback, this);
2929

3030
recovery_mode_flag_server_ =
31-
nh_.advertiseService("/recovery/available", &MotionDecision::recovery_mode_flag_callback, this);
32-
task_stop_flag_server_ = nh_.advertiseService("/task/stop", &MotionDecision::task_stop_flag_callback, this);
31+
nh_.advertiseService("recovery/available", &MotionDecision::recovery_mode_flag_callback, this);
32+
task_stop_flag_server_ = nh_.advertiseService("task/stop", &MotionDecision::task_stop_flag_callback, this);
3333

3434
load_params();
3535
if (params_.use_360_laser || params_.use_local_map)

0 commit comments

Comments
 (0)