Browse Source

Change fake driver (#4)

* Change fake driver

* Add velocity state interfaces
feature/ros2_diffdrive
David V. Lu!! 3 years ago
committed by GitHub
parent
commit
c354219ff6
No known key found for this signature in database GPG Key ID: 4AEE18F83AFDEB23
2 changed files with 10 additions and 2 deletions
  1. +3
    -1
      stretch_moveit_config/config/gripper.ros2_control.xacro
  2. +7
    -1
      stretch_moveit_config/config/stretch_arm.ros2_control.xacro

+ 3
- 1
stretch_moveit_config/config/gripper.ros2_control.xacro View File

@ -5,17 +5,19 @@
<ros2_control name="${name}" type="system">
<hardware>
<plugin>fake_joint_driver/FakeJointDriver</plugin>
<plugin>fake_components/GenericSystem</plugin>
</hardware>
<joint name="joint_gripper_finger_left">
<param name="start_position">0.0</param>
<command_interface name="position" />
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
<joint name="joint_gripper_finger_right">
<param name="start_position">0.0</param>
<command_interface name="position" />
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
</ros2_control>

+ 7
- 1
stretch_moveit_config/config/stretch_arm.ros2_control.xacro View File

@ -5,37 +5,43 @@
<ros2_control name="${name}" type="system">
<hardware>
<plugin>fake_joint_driver/FakeJointDriver</plugin>
<plugin>fake_components/GenericSystem</plugin>
</hardware>
<joint name="joint_arm_l0">
<param name="start_position">0.0</param>
<command_interface name="position" />
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
<joint name="joint_arm_l1">
<param name="start_position">0.0</param>
<command_interface name="position" />
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
<joint name="joint_arm_l2">
<param name="start_position">0.0</param>
<command_interface name="position" />
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
<joint name="joint_arm_l3">
<param name="start_position">0.0</param>
<command_interface name="position" />
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
<joint name="joint_lift">
<param name="start_position">0.1033</param>
<command_interface name="position" />
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
<joint name="joint_wrist_yaw">
<param name="start_position">0.0</param>
<command_interface name="position" />
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
</ros2_control>

Loading…
Cancel
Save