My robot blows up when I launch the controllers [update 2]
EDIT2: I have forked the gazebo_ros_demos package to try a velocity control on the rrbot simple robot.
Here is the link to my repo: https://github.com/Arn-O/gazeborosdemos.git
I have changed something in the configuration files.
VelocityJointInterface and no longer EffortJointInterface:
<transmission name="tran2">
<type>transmission_interface/SimpleTransmission</type>
<joint name="joint2"/>
<actuator name="motor2">
<hardwareInterface>VelocityJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
\velocitycontrollers and no longer \effortcontrollers:
rrbot:
joint1_position_controller:
type: effort_controllers/JointPositionController
joint: joint1
pid: {p: 100.0, i: 0.01, d: 10.0}
joint2_velocity_controller:
type: velocity_controllers/JointVelocityController
joint: joint2
pid: {p: 100.0, i: 0.01, d: 10.0}
The robot does not explode with this configuration, but I do not have the expected effect. The joint2 is not animated.
EDIT: this is related to the velocity controller. I had another issue before the upgrade, see answer.
Hello.
I have upgraded the source code of the package required for the installation of Gazebo 1.9 and ROS, and now my robot blows up when I launch the controllers. (EDIT: it is fine without the velocity controllers).
Before the controllers:
After:
It looks like everything has collapsed to the origin point of my robot, like if there were no joints.
It was working fine before the update (expect the velocity controller). (EDIT: I had the usse described in the following answer).
Any idea?
Thx in advance!
EDIT: additional details.
Here is the definition of the elements of my robot related to this topic.
...
<joint name="wheel_joint_fl" type="continuous">
<axis xyz="0 1 0"/>
<limit effort="${wheel_joint_effort}" velocity="${wheel_joint_velocity}"/>
<origin xyz="${wheel_offset_x} ${wheel_offset_y} ${wheel_offset_z}" rpy="0 0 0"/>
<parent link="caster_link_fl"/>
<dynamics damping="${wheel_joint_damping}" friction="${wheel_joint_friction}"/>
<safety_controller k_velocity="${wheel_joint_safety_k_velocity}"/>
<child link="wheel_link_fl"/>
</joint>
...
Definition of the transmission:
...
<transmission name="wheel_trans_fl">
<type>transmission_interface/SimpleTransmission</type>
<joint name="wheel_joint_fl"/>
<actuator name="wheel_motor_fl">
<hardwareInterface>EffortJointInterface</hardwareInterface>
<mechanicalReduction>${wheel_mechanical_reduction}</mechanicalReduction>
</actuator>
</transmission>
...
Launch file for the controllers:
...
<node name="controller_spawner" pkg="controller_manager"
type="spawner" respawn="false" output="screen"
ns="/youbot" args="--namespace=/youbot
wheel_joint_fl_velocity_controller
wheel_joint_fr_velocity_controller
wheel_joint_bl_velocity_controller
wheel_joint_br_velocity_controller
caster_joint_fl_position_controller
caster_joint_fr_position_controller
caster_joint_bl_position_controller
caster_joint_br_position_controller
arm_joint_1_position_controller
arm_joint_2_position_controller
arm_joint_3_position_controller
arm_joint_4_position_controller
arm_joint_5_position_controller
gripper_finger_joint_l_position_controller
gripper_finger_joint_r_position_controller" />
<!-- Load joint controller configurations from YAML file to parameter server -->
<rosparam file="$(find youbot_control)/config/youbot_control.yaml" command="load" />
...
And parameters of the controllers:
youbot:
wheel_joint_fl_velocity_controller:
type: effort_controllers/JointVelocityController
joint: wheel_joint_fl
pid: {p: 100.0, i: 0.01, d: 10.0}
wheel_joint_fr_velocity_controller:
type: effort_controllers/JointVelocityController
joint: wheel_joint_fr
pid: {p: 100.0, i: 0.01, d: 10.0}
wheel_joint_bl_velocity_controller:
type: effort_controllers/JointVelocityController
joint: wheel_joint_bl
pid: {p: 100.0, i: 0.01, d: 10.0}
wheel_joint_br_velocity_controller:
type: effort_controllers/JointVelocityController
joint: wheel_joint_br
pid: {p: 100.0, i: 0.01, d: 10.0}
...
I have no error message when the bug is triggered. I do not know if there is a useful log somewhere.
I can create a simple rrbot like with a velocity controller to investigate the point (the tutorial has been very helpful).
Can you explain what controllers you are running, and how you are running them. What version of ROS are you using? We'll also need to see the controllers.
Hello Nate. Gazebo = 1.9.5, ROS = hydro, and the controllers come from the source on GitHub. I hope that answer your question, there should be a way to have a detailed log, but I did not find it. I will update the above message with my tries on rrbot.