Closed dabhijeet closed 4 years ago
Hello, are you using our PRBT manipulator?
No. We are not using PRBT manipulator. Please find the rqt_graph of our system
Vibrations in robots can be caused by a number of different things, all of which would require different approaches.
You may have to provide a little more info on how you exactly "integrated pilz_industrial_motion with [y]our robot".
What sort of control interfaces are you using? How is it executing motion/trajectories coming from ROS? What sort of control system does it have? Is there any (low-level) filtering in the robot controller? If so: what? Does it have any specific (continuity) requirements to incoming trajectories. Etc.
We are using EtherCAT communication and Position Trajectory controller for our robot. The robot is moving smoothly with MoveIt Commander (Python). For jogging we are using jog_control from https://github.com/tork-a/jog_control and the robot is jogging smoothly in joint as well as in linear.
We integrated with pilz_industrial_motion by changing the below parameters according to our robot
_DEFAULT_PLANNING_GROUP = "arm" _DEFAULT_TARGET_LINK = "tcp" _DEFAULT_GRIPPER_PLANNING_GROUP = "gripper" _DEFAULT_BASE_LINK = "Link_1"
Also we commented the exceptions.py so that there won't be error related to BrakeTestErrorCodes. Also we specified planner pilz::CommandPlanner and the capabilities pilz_trajectory_generation/MoveGroupSequenceAction and pilz_trajectory_generation/MoveGroupSequenceService in moveit and used robot_state_publisher in moveit.
I think mostly it will be problem with connections between node.
I think that the problem may lie in the controller of your robot. Lets give a bit of background: Our planners (both LIN and PTP) are using trapezoidal speed profiles. This means that they can produce high jerk values. This is normally not a problem, because it is the responsibility of the controller to limit these and to smooth out the motion. Can you please help us reproduce your issue:
vel_scale=0.1, acc_scale=0.1
https://github.com/PilzDE/pilz_industrial_motion/blob/melodic-devel/pilz_robot_programming/Readme.rst#sequenceOtherwise, I am afraid we can not reproduce the problem.
When we set vel_scale=0.1 and acc_scale=0.1 we get some vibrations in LINEAR and when we increase the vel_scale or acc_scale , the amplitude of vibration increases. Although there is no vibration in JOINT PTP motion even at high speed and acceleration. There is one more observation that if we use OMPL instead of pilz_command_planner then we don't get the vibration in linear even at high velocity and acceleration although the path traveled in linear is not straight in this case.
In simulation there is no problem in linear as well as in joint even at high velocity and acceleration. We are observing vibration only in the real robot.
We have tried tuning the controller but didn't get good results. I am sharing the controller yaml file
# Publish all joint states -----------------------------------
joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: 50
# Position - Right and Left Joint Position Trajectory Controllers -------------------
position_trajectory_controller:
type: "position_controllers/JointTrajectoryController"
joints:
- Joint_1
- Joint_2
- Joint_3
- Joint_4
- Joint_5
- Joint_6
gains:
Joint_1: {p: 10000, d: 100, i: 100, i_clamp: 1}
Joint_2: {p: 10000, d: 100, i: 100, i_clamp: 1}
Joint_3: {p: 10000, d: 100, i: 100, i_clamp: 1}
Joint_4: {p: 10000, d: 100, i: 100, i_clamp: 1}
Joint_5: {p: 10000, d: 100, i: 100, i_clamp: 1}
Joint_6: {p: 10000, d: 100, i: 100, i_clamp: 1}
constraints:
goal_time: 0.3 #Tolerence of goal time
stopped_velocity_tolerance: 0.6 #Changing this value, can remove the trajectory error aborted message
Joint_1: {trajectory: 0.01, goal: 0.01}
Joint_2: {trajectory: 0.01, goal: 0.01}
Joint_3: {trajectory: 0.01, goal: 0.01}
Joint_4: {trajectory: 0.01, goal: 0.01}
Joint_5: {trajectory: 0.01, goal: 0.01}
Joint_6: {trajectory: 0.01, goal: 0.01}
state_publish_rate: 50 # Defaults to 50
action_monitor_rate: 20 # Defaults to 20
#hold_trajectory_duration: 0 # Defaults to 0.5
If this is only in LIN and not for PTP: What inverse kinematics solver do you use? Is there any option to increase the precision of solutions?
We are using TrackIK and there is no effect by changing the parameter of IK.
To isolate controller vs. trajectory generation please have a look at the generated trajectory in position_trajectory_controller/command
. Does that trajectory look smooth? Does it deviate from the joint_states during execution?
@dabhijeet: did you solve the problem?
Hello,
We integrated pilz_industrial_motion with our robot. All the functions are working fine like PTP, LIN, CIRC, Sequence and blend in real robot. The only issue we are getting now is vibrations while using LIN in the real robot. There is no vibration in PTP. When we use simulation we don't have vibration at all but in real robot we see vibrations in LIN. We have kept the catesian limits as per our robot. cartesian_limits: max_trans_vel: 1.2 max_trans_acc: 1.2 max_trans_dec: -1.2 max_rot_vel: 1.2
also in the moveit launch file we have added
Any idea why this might be happening?