-
Notifications
You must be signed in to change notification settings - Fork 85
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
Real Arm is shaking when using Moveit Servo #2
Comments
This is the config file for the servoing:
|
Hi @lorepieri8 Thanks for your feedback. To be honest we have not tested with Moveit Servo yet. I guess you can try controlling with higher frequency (normally we use 100Hz in Moveit application) and make sure the network connection with xArm controller is stable and low-latency (by cable connection and no switches in-between). Another test may be controlling with velocity interface, by bringing up xArm with Please be sure to test with a low operation velocity and always keep the emergency button reachable. We will arrange the compatibility test with Moveit Servo accordingly. |
Thanks for the quick response @penglongxiang . I tried pushing the update_rate to 100 Hz in Regarding the second option (velocity_control:=true), the real arm doesn't move at all. The simulation is still fine and works without issues. |
I'm using firmware version 1.6.1, perhaps that's why velocity control is not working? EDIT: No, the problem is still there after update to 1.7.2. |
Hi @lorepieri8 , thank you for reporting these issues, we suggest not to use "moveit_servo" with xArm until we fully test and support this new function, otherwise the behavior can be unpredictable and dangerous. We will notify you once the support is ready. |
@lorepieri8 we have tested moveit servo function these days and found out specifying However, please DO NOT USE VELOCITY MODE with Moveit Servo, the command generated this way is not stable, we are still trying to figure out the reason. Position control (by default) with |
I've tried as you suggested:
but the shaking is still there.
I do get about 100 hz. |
Hi @lorepieri8 have you made any changes in xarm_controller/config/xarm6_controllers.yaml? Could you also send us the controller log after reproducing this shaking phenomenon? Log can be downloaded through xArm studio: Settings->System->Log->Download. You may send it to [email protected] |
No edits to the yaml. I've sent the logs, thanks for your support. |
Hi @lorepieri8 , it looks like two controlling sources are conflicting, one is from move_group and the other is from joystick. Could you share the modified |
Hi @penglongxiang , I think we are on the right track, there are many duplicates. https://gist.github.com/lorepieri8/9eaebf8f6355752dfdd26227bcdae072
|
Hi @lorepieri8 , it is still not recommended to run xarm_moveit_config application along with other controlling nodes. I think the above issue is due to duplicated launch of several nodes, the commands or states are not consistent but eventually all goes to the same hardware. Still, after some modification, we managed to run import os
import yaml
from launch import LaunchDescription
from launch_ros.actions import Node
from ament_index_python.packages import get_package_share_directory
from launch_ros.actions import ComposableNodeContainer
from launch_ros.descriptions import ComposableNode
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
from launch.launch_description_sources import load_python_launch_file_as_module
from launch_ros.substitutions import FindPackageShare
from launch.actions import OpaqueFunction, IncludeLaunchDescription
import xacro
def load_yaml(package_name, file_path):
package_path = get_package_share_directory(package_name)
absolute_file_path = os.path.join(package_path, file_path)
try:
with open(absolute_file_path, "r") as file:
return yaml.safe_load(file)
except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available
return None
def launch_setup(context, *args, **kwargs):
# *** CUSTOMIZE HERE! Your Moveit Servo Configuration file
servo_yaml = load_yaml('xarm_moveit_servo', "config/xarm_moveit_servo_config.yaml")
servo_params = {"moveit_servo": servo_yaml}
dof = LaunchConfiguration('dof', default=6)
hw_ns = LaunchConfiguration('hw_ns', default='xarm')
moveit_config_package_name = 'xarm_moveit_config'
# robot_description_parameters
mod = load_python_launch_file_as_module(os.path.join(get_package_share_directory(moveit_config_package_name), 'launch', 'lib', 'xarm_moveit_config_lib.py'))
get_xarm_robot_description_parameters = getattr(mod, 'get_xarm_robot_description_parameters')
robot_description_parameters = get_xarm_robot_description_parameters(
xacro_urdf_file=PathJoinSubstitution([FindPackageShare('xarm_description'), 'urdf', 'xarm_device.urdf.xacro']),
xacro_srdf_file=PathJoinSubstitution([FindPackageShare('xarm_moveit_config'), 'srdf', 'xarm.srdf.xacro']),
urdf_arguments={
'dof': dof,
'hw_ns': hw_ns,
},
srdf_arguments={
'dof': dof,
},
arguments={
'xarm_type': 'xarm{}'.format(dof.perform(context)),
}
)
# Launch as much as possible in components
container = ComposableNodeContainer(
name="xarm_moveit_servo_container",
namespace="/",
package="rclcpp_components",
executable="component_container",
composable_node_descriptions=[
ComposableNode(
package="moveit_servo",
plugin="moveit_servo::ServoServer",
name="servo_server",
parameters=[
servo_params,
robot_description_parameters
],
extra_arguments=[{"use_intra_process_comms": True}],
),
# *** CUSTOMIZE HERE! Node to map JoyStick signal to robot command. (In the Constructor, it is better
# to add a delay before subscriber, incase robot initial position is not yet updated to latest)
ComposableNode(
package='xarm_moveit_servo',
plugin='xarm_moveit_servo::JoyToServoPub',
name='joy_to_servo_node',
parameters=[
servo_params,
{'dof': dof, 'ros_queue_size': 10},
],
extra_arguments=[{'use_intra_process_comms': True}],
),
ComposableNode(
package="joy",
plugin="joy::Joy",
name="joy_node",
extra_arguments=[{"use_intra_process_comms": True}],
),
],
output="screen",
)
return [container]
def generate_launch_description():
return LaunchDescription([
OpaqueFunction(function=launch_setup)
]) Please modify according to the "CUSTOMIZE HERE" instructions in the code, and test on your side. In this way, there may be no conflict when controlling with joystick when moveit_config application is still running. (1) pay attention to the "add a delay" suggestion, there may be a chance the joint states are not properly updated at 'joy_to_servo_node' startup and joints may go directly to all-zero position. We may add a demo package for moveit_servo control with joystick later, but it is supposed to run alone, not together with moveit-config. |
@lorepieri8 @penglongxiang |
Hi @MeticulousFishFrier, if you consider switching to ROS2, we already updated a demo package for moveit_servo control. Refer here. |
Hi @penglongxiang, I just tested the moveit_servo on a real XArm7 using an XBOX controller. The arm responds to the input commands well, but it still shakes for every movement. I presume this is because every time a new command is sent to the arm by ROS, its joint velocities restart at 0 and accelerate. Is this due to a limitation in the firmware or could a smooth trajectory be achieved with moveit_servo? |
Hi @MeticulousFishFrier |
@penglongxiang, I have the latest firmware on my xArm7 (1.8.3). The command used was the one you mentioned. Please test with the command |
Hi @MeticulousFishFrier please try not to use velocity control first, we are still evaluating the velocity interpolation by moveit, sometimes the velocity command is abnormal and oscillating. After our test, the performance under position control seems OK if the network connection is direct and stable. Please try updating Sometimes if moveit_servo believes the robot is reaching singularity, the command can be slowed down in the middle or even stalled. If this can not solve your problem, maybe a video showing the shaking is better for further diagnose. |
I changed the update_rate to be 100 and the execution did become smoother. Although I'm not sure at what the ranges of the frequencies can be, higher frequencies made the execution even smoother! Thank you so much for the fix!! Do you know how this |
We use "ros2_control_node" provided by "ros2_control" package to implement the controller logic, you can see from its code: which uses the " For ROS1, it is a different but similar logic, you may change the " Please note the maximun frequency xArm series can respond to is 250Hz. |
I changed the update_rate variable in xarm_controller/src/xarm_control_node.cpp in ROS1 but the arm is still jittering. Is there any reason why the same variable change isn't changing the behavior? |
I found the issue. The topic |
In ROS1, you can specify |
Thanks for your help @penglongxiang . We were able to achieve super smooth motions in ROS1 by adding our own JointGroupVelocityControl controller and |
@MeticulousFishFrier @lorepieri8 I hope you are doing well. I am trying to run moveit servoing, I am following the steps
My config file looks like
I am not sure why my arm is not moving, do we have to change the controller, can you please guide me through this how you moved in ros1 ? I am kind of struck at it since very long time. I think I am doing something wrong with the controller as I am not changing the controller right now. Thank You |
The lite6 is also shaking quite a bit for me when I run MoveIt Servo :(. |
@MeticulousFishFrier was your code merged? |
@peterdavidfagan you are using ros1 or ros2? |
@MeticulousFishFrier Hi, can you please share the JointGroupVelocityControl controller file? |
Hi @Akumar201 I have been using ROS 2. I am revisiting this now, I still observe shaking. Did you get to resolve this issue in ROS 2? @penglongxiang do you have any advice for this, I am planning on deploying learnt policies on the robot arm and solving this issue would really help. ROS Workspace Reproduce
Qualitative Behaviour Note: initial motion is using regular motion planning, after this you can see the camera shaking in the background as the robot moves from one target to the next using |
Hi @peterdavidfagan, I can not locate your |
Thanks @penglongxiang I have altered the setup such that the controller runs on a RT patched Intel NUC, I am awaiting a network switch to test the entire setup (client currently runs on laptop within the given network), once these components are ready I will follow the above advice and post my findings here. I did test updating the controller |
OK, maybe just increasing |
Ok I got servo to work smoothly but only using a Direct position control at 250hz using Edit: I will look to plot control commands and provide these results tomorrow as part of debugging direct position control. |
@penglongxiang despite setting the controller frequency and state publisher to 250hz there always appears to be a mismatch between how frequently control commands are issued and the state is published. I am also seeing step like behaviour in the velocity profile. The controller appears to rapidly accelerate towards the new target once it receives joint state information, then it remains at a constant velocity according the the published velocity until the next joint state is read. Despite updating the state publisher, it seems that the state always publishes as 5hz. Strangely the |
@MeticulousFishFrier, how did you get your state publishing at 100hz? I have altered the state publisher in my ros2_control config but I still get 5hz from Joint Trajectory Controller Position Controller @penglongxiang I believe if I can read |
For others who are facing similar issues the ROS 1 readme specifies the following: https://github.com/xArm-Developer/xarm_ros#report_type-argument A similar but less detailed specification can be found in the ROS 2 readme. Update: I have gotten |
Got position control working as well, below is an example of running direct position control at 100hz. |
@lorepieri8 is this issue considered resolved? |
Glad to know the issue was solved on your side. According to this line, the default |
Thanks @penglongxiang I was launching with custom launch files hence the ufactory driver was being launched with the wrong report type. |
I will close this issue as it seems can be solved by specifying |
I've adapted the real time servoing tutorial to work with Xarm6. All good in simulation, both using the ros2_control_plugin fake_components/GenericSystem (as done in the Panda tutorial) and the gazebo_ros2_control/GazeboSystem. I'm using a PS3 joystick to control joints and cartesian movements.
If I use xarm_control/XArmHW with Gazebo it's also fine, but when working with the real arm, the arm starts shaking and it hardly moves.
To control the real arm I'm using:
ros2 launch xarm_moveit_config xarm6_moveit_realmove.launch.py robot_ip:=myip
and
ros2 launch moveit2_tutorials servo_teleop.launch.py
What is causing the shaking? Do I have to tune any PID values? Or perhaps should I set a lower frequency for the controllers?
The text was updated successfully, but these errors were encountered: