Skip to main content
All CollectionsxArm-ROS/ Kinematics and Dynamics
Solve the problem that all joints of the xArm are at '0' in the gazebo
Solve the problem that all joints of the xArm are at '0' in the gazebo

Guide the user to solve the problem that all joints of the UFACTORY xArm are at 0 in the gazebo .

W
Written by Wang Daniel
Updated over 3 years ago

Examples are valid for:

ROS version: Kinetic
Ubuntu version: ubuntu-16.04

This problem is shown in the figure.

When executing "roslaunch  xarm_gazebo  xarm6_beside_table.launch  run_demo: = true", all joints of the UFACTORY xArm are at 0 in the gazebo.

Solutions

●  Comment out the Pid parameter of the joint under the gazebo_ros_control module      in the xarm6_traj_controller file.
● Comment out the Pid parameter of the joint under the gazebo_ros_control module in the xarm6_position_controllers file.
●   Save the xarm6_traj_controller.yaml and the xarm6_position_controllers.yaml

The directory of the xarm6_traj_controller file: src/xarm_controller/config/xarm6_traj_controller.yaml

xarm:    
  joint_state_controller:      
  type: joint_state_controller/JointStateController      
  publish_rate: 50
         
xarm6_traj_controller:      
  type: position_controllers/JointTrajectoryController      
  joints:        
     - joint1        
     - joint2        
     - joint3        
     - joint4        
     - joint5        
     - joint6      
constraints:          
  goal_time: 0.5          
  stopped_velocity_tolerance: 0.05          
  joint1: {trajectory: 1, goal: 0.01}          
  joint2: {trajectory: 1, goal: 0.01}          
  joint3: {trajectory: 1, goal: 0.01}          
  joint4: {trajectory: 1, goal: 0.01}          
  joint5: {trajectory: 1, goal: 0.01}          
  joint6: {trajectory: 1, goal: 0.01}      
stop_trajectory_duration: 0.2      
state_publish_rate:  25      
action_monitor_rate: 10      

# No Pid gains specified error fix    
# gazebo_ros_control:    
#   pid_gains:    
#     joint1: {p: 1200.0, i: 5.0, d: 10.0}    
#     joint2: {p: 1400.0, i: 5.0, d: 10.0}    
#     joint3: {p: 1200.0, i: 5.0, d: 5.0}    
#     joint4: {p: 850.0, i: 3.0, d: 5.0}    
#     joint5: {p: 500.0, i: 3.0, d: 1.0}    
#     joint6: {p: 500.0, i: 1.0, d: 1.0} 


The directory of the xarm6_position_controllers file: src/xarm_controller/config/xarm6_position_controllers.yaml

xarm: 
# Publish all joint states ----------------------------------- joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: 50

# Position Controllers --------------------------------------- joint1_position_controller:
type: position_controllers/JointPositionController
joint: joint1
pid: {p: 1200.0, i: 5.0, d: 10.0}
joint2_position_controller:
type: position_controllers/JointPositionController
joint: joint2
pid: {p: 1400.0, i: 5.0, d: 10.0}
joint3_position_controller:
type: position_controllers/JointPositionController
joint: joint3
pid: {p: 1200.0, i: 5.0, d: 5.0}
joint4_position_controller:
type: position_controllers/JointPositionController
joint: joint4
pid: {p: 850.0, i: 3.0, d: 5.0}
joint5_position_controller:
type: position_controllers/JointPositionController
joint: joint5
pid: {p: 500.0, i: 3.0, d: 1.0}
joint6_position_controller:
type: position_controllers/JointPositionController
joint: joint6
pid: {p: 500.0, i: 1.0, d: 1.0}

# No Pid gains specified error fix
# gazebo_ros_control:
# pid_gains:
# joint1: {p: 1200.0, i: 5.0, d: 10.0}
# joint2: {p: 1400.0, i: 5.0, d: 10.0}
# joint3: {p: 1200.0, i: 5.0, d: 5.0}
# joint4: {p: 850.0, i: 3.0, d: 5.0}
# joint5: {p: 500.0, i: 3.0, d: 1.0}
# joint6: {p: 500.0, i: 1.0, d: 1.0}

●  After the problem is solved, execute the following commands, xArm will move              normally in gazebo, see the following video.

source devel/set.bash
roslaunch xarm_gazebo xarm6_beside_table.launch run_demo:=true



Did this answer your question?