Skip to content

Commit

Permalink
hubero_ros - NavigationRos nav stack interface topic names published …
Browse files Browse the repository at this point in the history
…to ParamServer as full names (unification)
  • Loading branch information
rayvburn committed Feb 20, 2022
1 parent 877c34a commit 4d843e6
Show file tree
Hide file tree
Showing 2 changed files with 24 additions and 20 deletions.
21 changes: 14 additions & 7 deletions hubero_ros/launch/actor.launch
Original file line number Diff line number Diff line change
Expand Up @@ -70,6 +70,13 @@
<arg name="nav_odometry_topic" default="nav/odom"/>
<arg name="nav_get_plan_tolerance" default="1.0"/>

<!-- Append 'nav' related topics to full topic name that includes specific actor named <actor_name> -->
<arg name="actor_nav_goal_topic" value="$(arg actor_ns)/$(arg nav_goal_topic)"/>
<arg name="actor_nav_cancel_topic" value="$(arg actor_ns)/$(arg nav_cancel_topic)"/>
<arg name="actor_nav_get_plan_topic" value="$(arg actor_ns)/$(arg nav_get_plan_topic)"/>
<arg name="actor_nav_command_topic" value="$(arg actor_ns)/$(arg nav_command_topic)"/>
<arg name="actor_nav_odometry_topic" value="$(arg actor_ns)/$(arg nav_odometry_topic)"/>

<!-- Sensor data launch parameters -->
<!-- NOTE: these must be used with caution - see details in 'actor_<sensor>_scan_topic' below -->
<arg name="base_scan_topic" default="laser_scan"/>
Expand All @@ -87,11 +94,11 @@
<param name="hubero_ros/simulator_frame" value="$(arg simulator_global_frame)"/>
<param name="hubero_ros/namespace" value="$(arg main_ns)"/>

<param name="hubero_ros/navigation/goal_topic" value="$(arg nav_goal_topic)"/>
<param name="hubero_ros/navigation/cancel_topic" value="$(arg nav_cancel_topic)"/>
<param name="hubero_ros/navigation/get_plan_srv" value="$(arg nav_get_plan_topic)"/>
<param name="hubero_ros/navigation/command_topic" value="$(arg nav_command_topic)"/>
<param name="hubero_ros/navigation/odometry_topic" value="$(arg nav_odometry_topic)"/>
<param name="hubero_ros/navigation/goal_topic" value="$(arg actor_nav_goal_topic)"/>
<param name="hubero_ros/navigation/cancel_topic" value="$(arg actor_nav_cancel_topic)"/>
<param name="hubero_ros/navigation/get_plan_srv" value="$(arg actor_nav_get_plan_topic)"/>
<param name="hubero_ros/navigation/command_topic" value="$(arg actor_nav_command_topic)"/>
<param name="hubero_ros/navigation/odometry_topic" value="$(arg actor_nav_odometry_topic)"/>
<param name="hubero_ros/navigation/nav_get_plan_tolerance" value="$(arg nav_get_plan_tolerance)"/>

<param name="hubero_ros/actor_frames/base" value="$(arg actor_base_frame)"/>
Expand Down Expand Up @@ -127,8 +134,8 @@
<arg name="global_planner_suffix" value="$(arg global_planner_suffix)"/>
<arg name="local_planner" value="$(arg local_planner)"/>
<arg name="local_planner_suffix" value="$(arg local_planner_suffix)"/>
<arg name="odom_topic" value="$(arg nav_odometry_topic)"/>
<arg name="cmd_vel_topic" value="$(arg nav_command_topic)"/>
<arg name="odom_topic" value="$(arg actor_nav_odometry_topic)"/>
<arg name="cmd_vel_topic" value="$(arg actor_nav_command_topic)"/>
<arg name="map_topic" value="$(arg map_topic_name)"/>
<arg name="base_scan_topic" value="$(arg actor_base_scan_topic)"/>
<arg name="rgbd_scan_topic" value="$(arg actor_rgbd_scan_topic)"/>
Expand Down
23 changes: 10 additions & 13 deletions hubero_ros/src/navigation_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -80,46 +80,43 @@ bool NavigationRos::initialize(
nh.searchParam("/hubero_ros/navigation/nav_get_plan_tolerance", param_nav_get_plan_tolerance);
nh.param(param_nav_get_plan_tolerance, nav_get_plan_tolerance_, 1.0);

// prepare name
std::string ns_nav = actor_name_ + "/";

// initialize publishers, service clients, subscribers
pub_mb_goal_ = node_ptr->getNodeHandlePtr()->advertise<move_base_msgs::MoveBaseActionGoal>(
ns_nav + topic_nav_goal,
topic_nav_goal,
PUBLISHER_QUEUE_SIZE
);

pub_mb_cancel_ = node_ptr->getNodeHandlePtr()->advertise<actionlib_msgs::GoalID>(
ns_nav + topic_nav_cancel,
topic_nav_cancel,
PUBLISHER_QUEUE_SIZE
);

srv_mb_get_plan_ = node_ptr->getNodeHandlePtr()->serviceClient<nav_msgs::GetPlan>(
ns_nav + srv_nav_get_plan
srv_nav_get_plan
);

sub_cmd_vel_ = node_ptr->getNodeHandlePtr()->subscribe(
ns_nav + topic_nav_cmd,
topic_nav_cmd,
SUBSCRIBER_QUEUE_SIZE,
&NavigationRos::callbackCmdVel,
this
);

pub_odom_ = node_ptr->getNodeHandlePtr()->advertise<nav_msgs::Odometry>(
ns_nav + topic_nav_odometry,
topic_nav_odometry,
PUBLISHER_QUEUE_SIZE
);

HUBERO_LOG("[%s].[NavigationRos] Initialized ROS interface\r\n"
HUBERO_LOG("[%s].[NavigationRos] Initialized ROS navigation stack interface\r\n"
"\t(pub) goal request topic at '%s'\r\n"
"\t(pub) goal cancel topic at '%s'\r\n"
"\t(srv) get plan client at '%s'\r\n"
"\t(sub) cmd vel topic at '%s'\r\n",
actor_name.c_str(),
(node_ptr->getNamespaceName() + "/" + ns_nav + topic_nav_goal).c_str(),
(node_ptr->getNamespaceName() + "/" + ns_nav + topic_nav_cancel).c_str(),
(node_ptr->getNamespaceName() + "/" + ns_nav + srv_nav_get_plan).c_str(),
(node_ptr->getNamespaceName() + "/" + ns_nav + topic_nav_cmd).c_str()
topic_nav_goal.c_str(),
topic_nav_cancel.c_str(),
srv_nav_get_plan.c_str(),
topic_nav_cmd.c_str()
);

return true;
Expand Down

0 comments on commit 4d843e6

Please sign in to comment.