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
while not rospy.is_shutdown():
pub1.publish(ArmCor1)
rate.sleep()
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>
Thank you guys for your help, it actually work after your comments. This was my 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>
I changed the limit section to this :
<limit
lower="0"
upper="3.14"
effort="2"
velocity="2.0" />
I have other problems like a very annoying shiver (that comes from effort value I think) but It is not for this topic.