ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

Action Server (Move Base Flex) not working in SMACH state machine: Still waiting for action server '/move_base_flex/get_path' to start… is it running?

asked 2020-10-05 10:38:29 -0600

Zimba96 gravatar image

I'm trying to implement a state machine (SMACH) that uses Move Base Flex following this tutorial.

Therefore, my state machine (which would be too complex to show completely here) proceed as follows:

1. State: launches all required launch-files that are necessary including the move base flex - launchfile using subprocess:

    ...
    try:
            log4 = open('/home/faps/catkin_ws/src/pathplanning/state_machine/logs/move_base_flex_log.txt', 'w')
            process4 = subprocess.Popen('roslaunch joggingblinde_2dnav move_base_flex.launch',
                                        stdout=log4, stderr=subprocess.STDOUT,
                                        shell=True, preexec_fn=os.setsid)
    except Exception:
            f = open("/home/faps/catkin_ws/src/pathplanning/state_machine/logs/main_log.txt", "a")
            f.write('state: ' + 'launch_service_nodes' + '; error: ' + 'Error in move_base_flex-node.\n')
            f.close()
            os.killpg(os.getpgid(process4.pid), signal.SIGTERM)
            userdata.in_termination_cause[0] = 'error'
            return 'aborted'
    ...

with the launch-file looking as follows:

    <launch>
      <!-- Move Base Flex -->
      <master auto="start"/>
      <node pkg="mbf_costmap_nav" type="mbf_costmap_nav" respawn="false" name="move_base_flex" output="screen">
      <param name="tf_timeout" value="1.5"/>
      <param name="planner_max_retries" value="3"/>
      <rosparam file="$(find joggingblinde_2dnav)/config/planners.yaml" command="load" />
      <rosparam file="$(find joggingblinde_2dnav)/config/costmap_common_params.yaml" command="load" ns="global_costmap"/>
      <rosparam file="$(find joggingblinde_2dnav)/config/costmap_common_params.yaml" command="load" ns="local_costmap" />
      <rosparam file="$(find joggingblinde_2dnav)/config/global_costmap_params.yaml" command="load" />
      <rosparam file="$(find joggingblinde_2dnav)/config/local_costmap_params.yaml" command="load" />
    </node>
  </launch>

2. State: computing new goalpoint and writing the resulting goalpoint into the corresponding userdata-variable. (I've tested this one: the goalpoint exists after this state, so it's not empty.)

3. State: calling the get_path action of move base flex like described in the linked tutorial above:

smach.StateMachine.add('GET_GLOBAL_PATH_IN_GOAL_CHECK_SM', 
                       smach_ros.SimpleActionState(
                           '/move_base_flex/get_path',
                           GetPathAction,
                           goal_slots=['target_pose'],
                           result_slots=['path']
                       ),
                       transitions={
                       'succeeded': 'FEEDBACK_IN_GOAL_CHECK_SM',
                       'aborted': 'SECURE_STATE_IN_GOAL_CHECK_SM',
                       'preempted': 'preempted'
                       },
                       remapping={
                       'target_pose': 'test_goal'
                       }
)

When running the state machine, everything works fine until state 3 is called which throws a warning:

'Still waiting for action server '/move_base_flex/get_path' to start... is it running?'

And after terminating the program using Ctrl+C, another error appears:

'Action server for /move_base_flex/get_path is not running.'

Most issue threads dealing with similar errors are caused because the given namespace is wrong or because the Action Server isn't running (which apparently can be checked by rostopic list).

Using rostopic list shows that the Action Server is running and that the namespace is correct as the following lines are do appear in the rostopic list - output:

/move_base_flex/current_goal
/move_base_flex/exe_path/cancel
/move_base_flex/exe_path/feedback
/move_base_flex/exe_path/goal
/move_base_flex/exe_path/result
/move_base_flex/exe_path/status
/move_base_flex/get_path/cancel
/move_base_flex/get_path/feedback
/move_base_flex/get_path/goal
/move_base_flex/get_path/result
/move_base_flex/get_path/status

Did I miss something? Any ideas on what could cause the error?

edit retag flag offensive close merge delete

2 Answers

Sort by » oldest newest most voted
2

answered 2020-10-12 07:41:28 -0600

Zimba96 gravatar image

Move Base Flex somehow appears to not work properly when started inside SMACH.

The Problem is that the action servers are started after the plugins are loaded, meaning that when mbf gets stuck loading the plugins, it won't start the action servers.

In my case, when starting mbf inside SMACH, it somehow fails to subscribe to the topics that are required by the costmap-plugin (due to the map-param of static layer) and therefore gets stuck.

Starting mbf outside of SMACH and THEN starting SMACH however works perfectly fine.

For more information, visit the corresponding issue thread.

edit flag offensive delete link more
0

answered 2020-11-11 03:47:18 -0600

jorge gravatar image

The Problem is that the action servers are started after the plugins are loaded, meaning that when mbf gets stuck loading the plugins, it won't start the action servers.

That's correct: costmap_navigation_server.cpp#L85; and it makes sense, actually, as you cannot provide any service until the plugins can execute it.

The problem I faced when using SMACH and MBF is that the state machine normally starts much faster than MBF (who expends a lot of time loading plugins), but the SimpleActionState don't wait for the action server to be alive (I suppose the idea is to speedup the startup) . My simple solution is to wait for move_base_flex/move_base action before running the SM:

def wait_for_mbf():
    """
    Wait for Move Base Flex's move_base action (the last to be started) getting available
    """
    mb_ac = actionlib.SimpleActionClient("/move_base_flex/move_base", mbf_msgs.MoveBaseAction)
    available = mb_ac.wait_for_server(rospy.Duration(30))
    if not available:
        rospy.logwarn("Move Base Flex not available after 30 seconds")
    return available

A bit hackish but works

edit flag offensive delete link more

Question Tools

Stats

Asked: 2020-10-05 10:38:29 -0600

Seen: 1,025 times

Last updated: Nov 11 '20