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

Update related to namespace #50

Merged
merged 1 commit into from
Dec 24, 2024
Merged
Show file tree
Hide file tree
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
30 changes: 15 additions & 15 deletions launch/motion_decision.launch
Original file line number Diff line number Diff line change
Expand Up @@ -36,17 +36,17 @@
<arg name="battery/full_charge_voltage" default="24.0"/>
<arg name="battery/cutoff_voltage" default="20.0"/>
<!-- Published topic -->
<arg name="cmd_vel" default="/cmd_vel"/>
<arg name="cmd_vel" default="cmd_vel"/>
<!-- Subscribed topics -->
<arg name="local_path/cmd_vel" default="/local_path/cmd_vel"/>
<arg name="local_map" default="/local_map"/>
<arg name="odom" default="/odom"/>
<arg name="front_laser/scan" default="/front_laser/scan"/>
<arg name="rear_laser/scan" default="/rear_laser/scan"/>
<arg name="battery_voltage" default="/battery_voltage"/>
<arg name="local_path/cmd_vel" default="local_path/cmd_vel"/>
<arg name="local_map" default="local_map"/>
<arg name="odom" default="odom"/>
<arg name="front_laser/scan" default="front_laser/scan"/>
<arg name="rear_laser/scan" default="rear_laser/scan"/>
<arg name="battery_voltage" default="battery_voltage"/>

<!-- run motion_decision node -->
<node pkg="motion_decision" type="motion_decision" name="motion_decision" ns="$(arg ns)" output="$(arg output)" respawn="true">
<node pkg="motion_decision" type="motion_decision" name="motion_decision" output="$(arg output)" respawn="true">
<!-- MotionDecisionParams -->
<param name="use_rear_laser" value="$(arg use_rear_laser)"/>
<param name="use_360_laser" value="$(arg use_360_laser)"/>
Expand Down Expand Up @@ -80,13 +80,13 @@
<param name="battery/full_charge_voltage" value="$(arg battery/full_charge_voltage)"/>
<param name="battery/cutoff_voltage" value="$(arg battery/cutoff_voltage)"/>
<!-- Published topic -->
<remap from="/cmd_vel" to="$(arg cmd_vel)"/>
<remap from="cmd_vel" to="$(arg cmd_vel)"/>
<!-- Subscribed topics -->
<remap from="/local_path/cmd_vel" to="$(arg local_path/cmd_vel)"/>
<remap from="/local_map" to="$(arg local_map)"/>
<remap from="/odom" to="$(arg odom)"/>
<remap from="/front_laser/scan" to="$(arg front_laser/scan)"/>
<remap from="/rear_laser/scan" to="$(arg rear_laser/scan)"/>
<remap from="/battery_voltage" to="$(arg battery_voltage)"/>
<remap from="local_path/cmd_vel" to="$(arg local_path/cmd_vel)"/>
<remap from="local_map" to="$(arg local_map)"/>
<remap from="odom" to="$(arg odom)"/>
<remap from="front_laser/scan" to="$(arg front_laser/scan)"/>
<remap from="rear_laser/scan" to="$(arg rear_laser/scan)"/>
<remap from="battery_voltage" to="$(arg battery_voltage)"/>
</node>
</launch>
28 changes: 14 additions & 14 deletions src/motion_decision.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,22 +14,22 @@

MotionDecision::MotionDecision(void) : private_nh_("~")
{
intersection_flag_pub_ = nh_.advertise<std_msgs::Bool>("/intersection_flag", 1, true);
cmd_vel_pub_ = nh_.advertise<geometry_msgs::Twist>("/cmd_vel", 1, true);

emergency_stop_flag_sub_ = nh_.subscribe("/emergency_stop", 1, &MotionDecision::emergency_stop_flag_callback, this);
front_laser_sub_ = nh_.subscribe("/front_laser/scan", 1, &MotionDecision::front_laser_callback, this);
joy_sub_ = nh_.subscribe("/joy", 1, &MotionDecision::joy_callback, this);
local_path_cmd_vel_sub_ = nh_.subscribe("/local_path/cmd_vel", 1, &MotionDecision::local_path_cmd_vel_callback, this);
local_map_sub_ = nh_.subscribe("/local_map", 1, &MotionDecision::local_map_callback, this);
odom_sub_ = nh_.subscribe("/odom", 1, &MotionDecision::odom_callback, this);
rear_laser_sub_ = nh_.subscribe("/rear_laser/scan", 1, &MotionDecision::rear_laser_callback, this);
battery_voltage_sub_ = nh_.subscribe("/battery_voltage", 1, &MotionDecision::battery_voltage_callback, this);
footprint_sub_ = nh_.subscribe("/footprint", 1, &MotionDecision::footprint_callback, this);
intersection_flag_pub_ = nh_.advertise<std_msgs::Bool>("intersection_flag", 1, true);
cmd_vel_pub_ = nh_.advertise<geometry_msgs::Twist>("cmd_vel", 1, true);

emergency_stop_flag_sub_ = nh_.subscribe("emergency_stop", 1, &MotionDecision::emergency_stop_flag_callback, this);
front_laser_sub_ = nh_.subscribe("front_laser/scan", 1, &MotionDecision::front_laser_callback, this);
joy_sub_ = nh_.subscribe("joy", 1, &MotionDecision::joy_callback, this);
local_path_cmd_vel_sub_ = nh_.subscribe("local_path/cmd_vel", 1, &MotionDecision::local_path_cmd_vel_callback, this);
local_map_sub_ = nh_.subscribe("local_map", 1, &MotionDecision::local_map_callback, this);
odom_sub_ = nh_.subscribe("odom", 1, &MotionDecision::odom_callback, this);
rear_laser_sub_ = nh_.subscribe("rear_laser/scan", 1, &MotionDecision::rear_laser_callback, this);
battery_voltage_sub_ = nh_.subscribe("battery_voltage", 1, &MotionDecision::battery_voltage_callback, this);
footprint_sub_ = nh_.subscribe("footprint", 1, &MotionDecision::footprint_callback, this);

recovery_mode_flag_server_ =
nh_.advertiseService("/recovery/available", &MotionDecision::recovery_mode_flag_callback, this);
task_stop_flag_server_ = nh_.advertiseService("/task/stop", &MotionDecision::task_stop_flag_callback, this);
nh_.advertiseService("recovery/available", &MotionDecision::recovery_mode_flag_callback, this);
task_stop_flag_server_ = nh_.advertiseService("task/stop", &MotionDecision::task_stop_flag_callback, this);

load_params();
if (params_.use_360_laser || params_.use_local_map)
Expand Down