test scene for pick and place
This commit is contained in:
parent
b4339edc19
commit
91f159e289
18 changed files with 219 additions and 133 deletions
|
@ -6,7 +6,7 @@ controller_manager:
|
|||
type: joint_trajectory_controller/JointTrajectoryController
|
||||
|
||||
rasmt_hand_controller:
|
||||
type: effort_controllers/JointGroupEffortController
|
||||
type: forward_command_controller/ForwardCommandController
|
||||
|
||||
joint_state_broadcaster:
|
||||
type: joint_state_broadcaster/JointStateBroadcaster
|
||||
|
@ -32,9 +32,4 @@ rasmt_hand_controller:
|
|||
joints:
|
||||
- rasmt_Slide_1
|
||||
- rasmt_Slide_2
|
||||
command_interfaces:
|
||||
- effort
|
||||
state_interfaces:
|
||||
- position
|
||||
- velocity
|
||||
- effort
|
||||
interface_name: position
|
|
@ -67,6 +67,10 @@ def generate_launch_description():
|
|||
executable="spawner.py",
|
||||
arguments=["rasmt_hand_controller", "--controller-manager", "/controller_manager"],
|
||||
)
|
||||
action_server_controller_hand_node = Node(
|
||||
package="robossembler_servers",
|
||||
executable="gripper_cmd_node"
|
||||
)
|
||||
|
||||
return LaunchDescription(
|
||||
launch_args + [
|
||||
|
@ -74,5 +78,6 @@ def generate_launch_description():
|
|||
robot_state_publisher,
|
||||
joint_state_broadcaster,
|
||||
controller_arm,
|
||||
controller_hand
|
||||
controller_hand,
|
||||
action_server_controller_hand_node
|
||||
])
|
|
@ -17,9 +17,9 @@
|
|||
</xacro:unless>
|
||||
|
||||
<joint name="${prefix}_Slide_1">
|
||||
<command_interface name="effort">
|
||||
<command_interface name="position">
|
||||
<!-- better to use radians as min max first -->
|
||||
<param name="min">-10</param>
|
||||
<param name="min">0</param>
|
||||
<param name="max">10</param>
|
||||
</command_interface>
|
||||
<state_interface name="position"/>
|
||||
|
@ -30,8 +30,8 @@
|
|||
<joint name="${prefix}_Slide_2">
|
||||
<!-- <param name="mimic">${prefix}_Slide_1</param>
|
||||
<param name="multiplier">1</param> -->
|
||||
<command_interface name="effort">
|
||||
<param name="min">-10</param>
|
||||
<command_interface name="position">
|
||||
<param name="min">0</param>
|
||||
<param name="max">10</param>
|
||||
</command_interface>
|
||||
<state_interface name="position"/>
|
||||
|
|
|
@ -52,7 +52,7 @@
|
|||
type="fixed">
|
||||
<origin
|
||||
xyz="0 0.0 0.12324"
|
||||
rpy="-3.14159265358979 0 -1.5707963267949" />
|
||||
rpy="-3.14159265358979 0 0" />
|
||||
<parent
|
||||
link="${prefix}_Dock_Link" />
|
||||
<child
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue