Problem with ROS control and Gazebo.
Hello,
I have a problem with controlling a URDF that I exported from SolidWorks. (Ubuntu 16.04 , Kinetic, Gazebo 7.x) I followed this tutorial and I wanted to implemented on my robot. All the controllers are starting correctly so as the Gazebo simulation also the Node publish the data correctly I have checked it with echo-ing the topic and with different values for the data. Is there a chance not working because the PID values ?
All the transmissions look like this :
<transmission name="tran1">
<type>transmission_interface/SimpleTransmission</type>
<joint name="Joint_1">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="motor1">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
The controller is like this (for all joints) :
joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: 50
joint1_position_controller:
type: effort_controllers/JointPositionController
joint: Joint_1
pid: {p: 100.0, i: 0.01, d: 10.0}
And I have this node:
rospy.init_node('ArmMovement')
pub1=rospy.Publisher("/rrbot/joint1_position_controller/command",Float64,queue_size=10 )
rate = rospy.Rate(50)
ArmCor1= Float64()
ArmCor1.data=0
pub1.publish(ArmCor1)
rate.sleep()
Edit#1 : Part of URDF for the Joint_1:
<joint name="Joint_1" type="revolute">
<origin
xyz="0 0 -0.008"
rpy="1.5708 0 0" />
<parent link="base_link" />
<child link="Link_1" />
<axis
xyz="0 1 0" />
<limit
lower="0"
upper="3.14"
effort="0"
velocity="0" />
</joint>
What is the behavior that you are seeing? IS it vibrating?
@pmuthu2s It has a little vibration but I believe it occurs because the gripper of the arm is touching the ground. There is no movement further than that.
Are there any warnings or errors when running your simulation? Is Gazebo loading your controllers correctly, is it publishing on the topic "/rrbot/joint1_position_controller/state" and subscribing to "/rrbot/joint1_position_controller/command" as expected?
No I dont have any warning or errors. The controllers are starting correclty and the message is successfully transimitted. @Jasmin
Could you post your urdf or at least the joint definition part?
@Jasmin. Of course, I have edited the question!
That helps! The joint will never move with a velocity="0". You need to set non zero effort and velocity values, try something like:
@Jasmin Thank you a lot for your help, it actually works!!