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

How do I disable execution_duration_monitoring ?

asked 2014-11-03 09:26:18 -0600

VictorLamoine gravatar image

updated 2017-01-12 07:46:26 -0600

I'm using the fanuc package for ROS-Industrial and when launching the moveit_planning_execution.launch I get the following error:

[ERROR] [1415027195.809289492]: Controller is taking too long to execute trajectory (the expected upper bound for the trajectory execution was 4.992567 seconds). Stopping trajectory.

The error is explained here. What I understand is that I have to add a line in one of the launch file, something like:

<param name="execution_duration_monitoring" value="false"/>

I tried 2 things without success:

trajectory_execution.launch.xml

  <!-- When determining the expected duration of a trajectory, this multiplicative factor is applied to get the allowed duration of execution -->
  <param name="allowed_execution_duration_scaling" value="1.2"/> <!-- default 1.2 -->
  <!-- Allow more than the expected execution time before triggering a trajectory cancel (applied after scaling) -->
  <param name="allowed_goal_duration_margin" value="0.5"/> <!-- default 0.5 -->
  <param name="execution_duration_monitoring" value="false"/>

And move_group.launch

<!-- Start the actual move_group node/action server -->
<node name="move_group" launch-prefix="$(arg launch_prefix)" pkg="moveit_ros_move_group" type="move_group" respawn="false" output="screen" args="$(arg command_args)">
<!-- Set the display variable, in case OpenGL code is used internally -->
<env name="DISPLAY" value="$(optenv DISPLAY :0)" />
<param name="allow_trajectory_execution" value="$(arg allow_trajectory_execution)"/>
<param name="max_safe_path_cost" value="$(arg max_safe_path_cost)"/>
<param name="jiggle_fraction" value="$(arg jiggle_fraction)" />
<param name="execution_duration_monitoring" value="false" />

What am I doing wrong?

edit retag flag offensive close merge delete

2 Answers

Sort by » oldest newest most voted
5

answered 2014-11-06 11:38:07 -0600

jowave gravatar image

updated 2014-11-12 05:34:59 -0600

From looking at the code, i think the parameter is in a sub namespace "trajectory_execution/". (Found in trajectory_execution_manager.cpp line 57)

The following should work in trajectory_execution.launch.xml

<param name="trajectory_execution/execution_duration_monitoring" value="false" />

Instead of disabling execution duration monitoring you can increase the time for your manipulator.

<param name="allowed_execution_duration_scaling" value="3.0"/>

Though, this param seems to exist in both namespaces?!

edit flag offensive delete link more

Comments

How did you find that the parameter is in a sub namespace?

VictorLamoine gravatar image VictorLamoine  ( 2014-11-12 02:39:01 -0600 )edit

the dynamic_reconfigure member is created with ros::NodeHandle("~/trajectory_execution")

jowave gravatar image jowave  ( 2014-11-12 05:35:25 -0600 )edit

I added it in execution.launch but the program is stuck without any error. Added it in trajectory_execution.launch.xml it doesn't work for me

here is the detailes: INFO] [1651917001.823645112]: RRTConnect: Starting planning with 1 states already in datastructure

Danielwang gravatar image Danielwang  ( 2022-05-07 04:47:19 -0600 )edit
3

answered 2016-06-06 16:03:44 -0600

MahdiehNejati gravatar image

We had the same issue with controlling a Kinova MICO arm using MoveIt!. Placing the following lines in our launch file seems to have fixed all issues related to controller time-out as well as goal tolerances.

<param name="move_group/trajectory_execution/allowed_execution_duration_scaling" value="4.0" />
<param name="move_group/trajectory_execution/execution_duration_monitoring" value="false" />

We found this by looking at the namespaces in rqt_reconfigure for move_group -> trajectory_execution.

Hope this helps!

edit flag offensive delete link more

Comments

Yes, it helped. Thank you .

nofear123 gravatar image nofear123  ( 2019-12-06 06:39:17 -0600 )edit

Wow, I can't believe I just ran into this post and still found it useful! Thanks, Rico

RicoJ gravatar image RicoJ  ( 2020-12-13 01:17:05 -0600 )edit

This helped me too! I only scaled up the allowed_execution_duration_scaling parameter to 4. I left the 'execution_duration_monitoring' param at its default value. I ran into another issue though where I was seeing a GOAL_TOLERANCE_VIOLATED error. However, increasing the goal_time parameter to '1' in my controllers.yaml file solved that issue. Note that this wasn't with a fanuc robot but with a custom arm I'm developing on.

swiz23 gravatar image swiz23  ( 2021-03-10 14:27:56 -0600 )edit

Question Tools

3 followers

Stats

Asked: 2014-11-03 09:15:19 -0600

Seen: 7,666 times

Last updated: Jan 12 '17