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

"Goal was rejected by server" with built-in fake controllers

asked 2022-06-08 11:10:28 -0500

smartin015 gravatar image

I'm porting an Annin Robotics AR3 MoveIt config that I didn't write to use MoveIt2 / ROS2. I've been merging together the configs in that repository with various breadcrumbs I picked up from the demo.launch.py file used in the tutorials.

I'm able to start all nodes and plan trajectories in rviz2 using fake controllers:

image

However I'm unable to execute the trajectory due to Goal request rejected. It's pretty likely I cargo culted something incorrectly along the way, but after a couple hours of searching I haven't found any leads on this error with the built-in stuff I've been using so far - I'd appreciate some help in confirming that my setup isn't obviously wrong.

environment

I'm using:

  • fake_components/GenericSystem plugin in the ros2_control tag within ar3_moveit2/config/ar3.urdf
  • JointTrajectoryController with FollowJointTrajectory in config/fake_controllers.yaml for ros2_control
  • The same JointTrajectoryController with MoveItSimpleControllerManager in config/moveit_controllers.yaml for moveit2

My robot has joint_1 through joint_6 configured in all the above locations.

Steps to reproduce

git clone -b moveit2 --single-branch https://github.com/smartin015/ar3_core.git && cd ar3_core docker-compose run gpu /bin/bash colcon build --mixin debug --packages-up-to ar3_moveit_config && source install/setup.bash && ros2 launch -d ar3_moveit_config demo.launch.py

An rviz window should open. With fixed_frame set to base_link, add a MotionPlanning display item, move the EEF a bit, then press Plan & Execute.

Expected behaviour

The plan should succeed and the arm move to the target position.

Actual behaviour

Plan succeeds, but the arm does not move and instead the console output below appears (notably with Goal was rejected by server).

Backtrace or Console output

https://gist.github.com/smartin015/23...

edit retag flag offensive close merge delete

Comments

Could you able to figure out this issue?. When i follow the panda moveit2 tutorial it works fine for me in the Rviz simulation. I did follow the similar for my custom robot, and it does not work, throws the same error as yours. I have no idea why it is not working. Mine was a 3-DOF robot arm.

Dp gravatar image Dp  ( 2022-06-13 10:57:11 -0500 )edit

I managed to get a bit further into debugging- look through your logs for a line containing:

Received new action goal.

When you find that line, look immediately after it - I had an error:

Time between points 0 and 1 is not strictly increasing, it is 0.000000 and 0.000000 respectively

I found the source of this error in joint_trajectory_controller.cpp. There are also other validation errors within validate_trajectory_msg() which may be the cause of the problem.

When I ran ros2 topic echo /display_planned_path, I saw all time_from_start values in my trajectory were indeed 0. This value seems to be set here, but I haven't dug deep enough to understand why.

smartin015 gravatar image smartin015  ( 2022-06-13 12:26:04 -0500 )edit

Hi I could able to make it work for my custom robot at least in simulation, you have to see the moveit_resources_panda_config folder in your /opt/ros/foxy/share path, look at the way the xacro files that are being used by panda ros2_control for fake execution, I adapted a similar way and it worked for me in simulation with one controller loaded. May be you have to add some files in your ar3 description packages. specially those xacro files. Let me know if it works for you. I guess that is the problem.

Dp gravatar image Dp  ( 2022-06-14 10:12:01 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
1

answered 2022-10-12 14:15:55 -0500

c_h_s gravatar image

This is probably because you are missing the correct ompl_planning.yaml. Time parameterization of the trajectory is done by a request adapter, so you need to tell moveit to use

Youl need to add this to your ompl_planning.yaml

request_adapters: >-
default_planner_request_adapters/AddTimeOptimalParameterization

Example is here:

https://github.com/ros-planning/movei...

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2022-06-08 11:10:28 -0500

Seen: 1,091 times

Last updated: Jun 08 '22