Skip to content

Commit

Permalink
Simulation improvements (#112)
Browse files Browse the repository at this point in the history
* Separate generators for robot and simulation handlers (#99)

* Created interface class and put the RPC handlers in robot folder

* Now the robot functions interface work just like before

* Added templates and generation for simulated services

* Added the simulation services to the driver headers

* Added newly generated files to repo

* Adapt simulation launch files and add prefix support for simulation and MoveIt (#100)

* Created interface class and put the RPC handlers in robot folder

* Now the robot functions interface work just like before

* Added templates and generation for simulated services

* Added the simulation services to the driver headers

* Added newly generated files to repo

* Added simulation option to the driver so the gazebo package can launch the kortex_driver too, in a different mode

* Adapt joint_limits files to correctly take prefix option

* Change description and control files to support prefix option

* Change MoveIt config launch and config files to enable prefix option - only SRDF modifications remain

* Added xacro usage in SRDF files to be able to prefix joint names

* Adjust ompl planning launch and config files to support prefixing joint names

* Remove --inorder from xacro calls since it's default now

* Create simulation handlers (#102)

* Created interface class and put the RPC handlers in robot folder

* Now the robot functions interface work just like before

* Added templates and generation for simulated services

* Added the simulation services to the driver headers

* Added newly generated files to repo

* Added simulation option to the driver so the gazebo package can launch the kortex_driver too, in a different mode

* Adapt joint_limits files to correctly take prefix option

* Change description and control files to support prefix option

* Change MoveIt config launch and config files to enable prefix option - only SRDF modifications remain

* Added xacro usage in SRDF files to be able to prefix joint names

* Adjust ompl planning launch and config files to support prefixing joint names

* Remove --inorder from xacro calls since it's default now

* Set default gripper in launch files

* Add namespace to launch file parameters passed to driver

* Added class and implementation for simulator

* Add stubs and register handlers for Action API

* Add implementation for default actions and ReacAction/ReadAllActions

* Added some unit tests for simulator and CreateAction implentation

* Added the case where the prefix could be empty in XACRO

* Added prefix support for fake controllers in MoveIt configs

* Added a missing prefix value for Gen3 and fix the if and unless tags

* Add test launch file to launch simulator unit tests

* Don't create the gripper Move Group if no gripper on the arm

* Added DeleteAction implementation and tests

* Add implementation and tests for UpdateAction

* Added basic frame for a threaded action executor

* Added publishing for action topic before and after action execution

* Added StopAction logic and tests for executing and aborting actions

* Added stubs for other RPCs we want to support at first in simulation

* Added implementation for other RPCs worth simulating

* Added some data structure checks and TODOs in executors

* Added tests for newly added RPCs

* Remove merge artefacts

* Implementation for angular position control, Cartesian position control and gripper position control (#105)

* Created interface class and put the RPC handlers in robot folder

* Now the robot functions interface work just like before

* Added templates and generation for simulated services

* Added the simulation services to the driver headers

* Added newly generated files to repo

* Added simulation option to the driver so the gazebo package can launch the kortex_driver too, in a different mode

* Adapt joint_limits files to correctly take prefix option

* Change description and control files to support prefix option

* Change MoveIt config launch and config files to enable prefix option - only SRDF modifications remain

* Added xacro usage in SRDF files to be able to prefix joint names

* Adjust ompl planning launch and config files to support prefixing joint names

* Remove --inorder from xacro calls since it's default now

* Set default gripper in launch files

* Add namespace to launch file parameters passed to driver

* Added class and implementation for simulator

* Add stubs and register handlers for Action API

* Add implementation for default actions and ReacAction/ReadAllActions

* Added some unit tests for simulator and CreateAction implentation

* Added the case where the prefix could be empty in XACRO

* Added prefix support for fake controllers in MoveIt configs

* Added a missing prefix value for Gen3 and fix the if and unless tags

* Add test launch file to launch simulator unit tests

* Don't create the gripper Move Group if no gripper on the arm

* Added DeleteAction implementation and tests

* Add implementation and tests for UpdateAction

* Added basic frame for a threaded action executor

* Added publishing for action topic before and after action execution

* Added StopAction logic and tests for executing and aborting actions

* Added stubs for other RPCs we want to support at first in simulation

* Added implementation for other RPCs worth simulating

* Added some data structure checks and TODOs in executors

* Added tests for newly added RPCs

* Remove merge artefacts

* Added implementation for ReachJointAngles action - optimal duration implementation remain

* Added KDL parsing and solvers construction

* Add max velocities and max accelerations to joint_limits.yaml files

* Add a helper to fill KortexError and finish velocity profiles implementation for ReachJointAngles

* Now use the velocity profile data to fill the trajectory

* Add implementation for angular position control

* Add same ROS parameters than real arm and adjust first timestamp to not be 0

* Fix MoveIt config Gen3 lite home position

* Added ReachPose implementation, twist limits still hardcoded

* Add twist limits files for simulation

* Use the correct Cartesian velocity and acceleration values for each arm and correctly use velocity limits in constraints

* Add simulated feedback support and change current state to fetch joint_states instead of controller state

* Added implementation for gripper control

* Fixed a Robotiq 2F-140 typo in the moveit config

* Added indexes for first arm joint and gripper joint because sometimes gripper joint is at the start of joint_states and sometimes it's at the end

* Address PR comments

* Fix tool frame for 6DOF Gen3 arm

* Simulation velocity control, documentation and examples update (#109)

* Created interface class and put the RPC handlers in robot folder

* Now the robot functions interface work just like before

* Added templates and generation for simulated services

* Added the simulation services to the driver headers

* Added newly generated files to repo

* Added simulation option to the driver so the gazebo package can launch the kortex_driver too, in a different mode

* Adapt joint_limits files to correctly take prefix option

* Change description and control files to support prefix option

* Change MoveIt config launch and config files to enable prefix option - only SRDF modifications remain

* Added xacro usage in SRDF files to be able to prefix joint names

* Adjust ompl planning launch and config files to support prefixing joint names

* Remove --inorder from xacro calls since it's default now

* Set default gripper in launch files

* Add namespace to launch file parameters passed to driver

* Added class and implementation for simulator

* Add stubs and register handlers for Action API

* Add implementation for default actions and ReacAction/ReadAllActions

* Added some unit tests for simulator and CreateAction implentation

* Added the case where the prefix could be empty in XACRO

* Added prefix support for fake controllers in MoveIt configs

* Added a missing prefix value for Gen3 and fix the if and unless tags

* Add test launch file to launch simulator unit tests

* Don't create the gripper Move Group if no gripper on the arm

* Added DeleteAction implementation and tests

* Add implementation and tests for UpdateAction

* Added basic frame for a threaded action executor

* Added publishing for action topic before and after action execution

* Added StopAction logic and tests for executing and aborting actions

* Added stubs for other RPCs we want to support at first in simulation

* Added implementation for other RPCs worth simulating

* Added some data structure checks and TODOs in executors

* Added tests for newly added RPCs

* Remove merge artefacts

* Added implementation for ReachJointAngles action - optimal duration implementation remain

* Added KDL parsing and solvers construction

* Add max velocities and max accelerations to joint_limits.yaml files

* Add a helper to fill KortexError and finish velocity profiles implementation for ReachJointAngles

* Now use the velocity profile data to fill the trajectory

* Add implementation for angular position control

* Add same ROS parameters than real arm and adjust first timestamp to not be 0

* Fix MoveIt config Gen3 lite home position

* Added ReachPose implementation, twist limits still hardcoded

* Add twist limits files for simulation

* Use the correct Cartesian velocity and acceleration values for each arm and correctly use velocity limits in constraints

* Add simulated feedback support and change current state to fetch joint_states instead of controller state

* Added implementation for gripper control

* Fixed a Robotiq 2F-140 typo in the moveit config

* Added indexes for first arm joint and gripper joint because sometimes gripper joint is at the start of joint_states and sometimes it's at the end

* Changed the way the individual position controllers are loaded and started as well as added service client in simulator to switch controllers based on RPC called

* Added implementation for angular velocity control and added joint limits to simulation class. Will need a way to wrap-around angles now that velocity control for infinite spinning joint is on.

* Added wrapping around in reach joint angles

* Fix a problem with timestamps

* Added an implementation for SendTwistCommand but not stable enough to be activated so handler is commented out

* Dont start the joint_7 controller for a 6DOF robot

* Changed the examples to use notifications to check whether an action is finished or not and removed the sleeps

* Put back the homing script for Gazebo and removed the copyright notice since we don't use MoveIt anymore to home the arm

* Adapt documentation for new simulation features

* Updated the package.xml's with bumped versions and author and maintainer tags

* Few minor tweaks in the examples

* Added a bit of details in the documentation
  • Loading branch information
alexvannobel authored Aug 5, 2020
1 parent 11e42a2 commit d2bf9e8
Show file tree
Hide file tree
Showing 240 changed files with 13,641 additions and 4,613 deletions.
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,73 +1,73 @@
# Publish all joint states -----------------------------------
joint_state_controller:
$(arg prefix)joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: 50

gen3_joint_trajectory_controller:
$(arg prefix)gen3_joint_trajectory_controller:
type: effort_controllers/JointTrajectoryController
joints:
- joint_1
- joint_2
- joint_3
- joint_4
- joint_5
- joint_6
- $(arg prefix)joint_1
- $(arg prefix)joint_2
- $(arg prefix)joint_3
- $(arg prefix)joint_4
- $(arg prefix)joint_5
- $(arg prefix)joint_6
constraints:
goal_time: 1.0
stopped_velocity_tolerance: 0.5
stop_trajectory_duration: 1.0
state_publish_rate: 25
action_monitor_rate: 25
gains:
joint_1: {p: 3000.0, i: 0.0, d: 2.0, i_clamp_min: -100.0, i_clamp_max: 100.0}
joint_2: {p: 50000.0, i: 0.0, d: 0.0, i_clamp_min: -5.0, i_clamp_max: 5.0}
joint_3: {p: 50000.0, i: 0.0, d: 0.0, i_clamp_min: -1.0, i_clamp_max: 1.0}
joint_4: {p: 750.0, i: 0.0, d: 0.2, i_clamp_min: -1.0, i_clamp_max: 1.0}
joint_5: {p: 5000.0, i: 0.0, d: 1.0, i_clamp_min: -1.0, i_clamp_max: 1.0}
joint_6: {p: 100.0, i: 0.0, d: 0.0, i_clamp_min: -0.1, i_clamp_max: 0.1}
$(arg prefix)joint_1: {p: 3000.0, i: 0.0, d: 2.0, i_clamp_min: -100.0, i_clamp_max: 100.0}
$(arg prefix)joint_2: {p: 50000.0, i: 0.0, d: 0.0, i_clamp_min: -5.0, i_clamp_max: 5.0}
$(arg prefix)joint_3: {p: 50000.0, i: 0.0, d: 0.0, i_clamp_min: -1.0, i_clamp_max: 1.0}
$(arg prefix)joint_4: {p: 750.0, i: 0.0, d: 0.2, i_clamp_min: -1.0, i_clamp_max: 1.0}
$(arg prefix)joint_5: {p: 5000.0, i: 0.0, d: 1.0, i_clamp_min: -1.0, i_clamp_max: 1.0}
$(arg prefix)joint_6: {p: 100.0, i: 0.0, d: 0.0, i_clamp_min: -0.1, i_clamp_max: 0.1}

joint_1_position_controller:
joint: joint_1
$(arg prefix)joint_1_position_controller:
joint: $(arg prefix)joint_1
pid:
p: 3000.0
i: 0.0
d: 2.0
type: effort_controllers/JointPositionController

joint_2_position_controller:
joint: joint_2
$(arg prefix)joint_2_position_controller:
joint: $(arg prefix)joint_2
pid:
p: 50000.0
i: 0.0
d: 0.0
type: effort_controllers/JointPositionController

joint_3_position_controller:
joint: joint_3
$(arg prefix)joint_3_position_controller:
joint: $(arg prefix)joint_3
pid:
p: 50000.0
i: 0.0
d: 0.0
type: effort_controllers/JointPositionController

joint_4_position_controller:
joint: joint_4
$(arg prefix)joint_4_position_controller:
joint: $(arg prefix)joint_4
pid:
p: 750.0
i: 0.0
d: 0.2
type: effort_controllers/JointPositionController

joint_5_position_controller:
joint: joint_5
$(arg prefix)joint_5_position_controller:
joint: $(arg prefix)joint_5
pid:
p: 5000.0
i: 0.0
d: 1.0
type: effort_controllers/JointPositionController

joint_6_position_controller:
joint: joint_6
$(arg prefix)joint_6_position_controller:
joint: $(arg prefix)joint_6
pid:
p: 100.0
i: 0.0
Expand Down
Original file line number Diff line number Diff line change
@@ -1,83 +1,83 @@
# Publish all joint states -----------------------------------
joint_state_controller:
$(arg prefix)joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: 50

gen3_joint_trajectory_controller:
$(arg prefix)gen3_joint_trajectory_controller:
type: effort_controllers/JointTrajectoryController
joints:
- joint_1
- joint_2
- joint_3
- joint_4
- joint_5
- joint_6
- joint_7
- $(arg prefix)joint_1
- $(arg prefix)joint_2
- $(arg prefix)joint_3
- $(arg prefix)joint_4
- $(arg prefix)joint_5
- $(arg prefix)joint_6
- $(arg prefix)joint_7
constraints:
goal_time: 1.0
stopped_velocity_tolerance: 0.5
stop_trajectory_duration: 1.0
state_publish_rate: 25
action_monitor_rate: 25
gains:
joint_1: {p: 3000.0, i: 0.0, d: 2.0, i_clamp_min: -100.0, i_clamp_max: 100.0}
joint_2: {p: 50000.0, i: 0.0, d: 0.0, i_clamp_min: -5.0, i_clamp_max: 5.0}
joint_3: {p: 3000.0, i: 0.0, d: 0.0, i_clamp_min: -1.0, i_clamp_max: 1.0}
joint_4: {p: 50000.0, i: 0.0, d: 0.0, i_clamp_min: -1.0, i_clamp_max: 1.0}
joint_5: {p: 750.0, i: 0.0, d: 0.2, i_clamp_min: -1.0, i_clamp_max: 1.0}
joint_6: {p: 5000.0, i: 0.0, d: 1.0, i_clamp_min: -1.0, i_clamp_max: 1.0}
joint_7: {p: 100.0, i: 0.0, d: 0.0, i_clamp_min: -0.1, i_clamp_max: 0.1}
$(arg prefix)joint_1: {p: 3000.0, i: 0.0, d: 2.0, i_clamp_min: -100.0, i_clamp_max: 100.0}
$(arg prefix)joint_2: {p: 50000.0, i: 0.0, d: 0.0, i_clamp_min: -5.0, i_clamp_max: 5.0}
$(arg prefix)joint_3: {p: 3000.0, i: 0.0, d: 0.0, i_clamp_min: -1.0, i_clamp_max: 1.0}
$(arg prefix)joint_4: {p: 50000.0, i: 0.0, d: 0.0, i_clamp_min: -1.0, i_clamp_max: 1.0}
$(arg prefix)joint_5: {p: 750.0, i: 0.0, d: 0.2, i_clamp_min: -1.0, i_clamp_max: 1.0}
$(arg prefix)joint_6: {p: 5000.0, i: 0.0, d: 1.0, i_clamp_min: -1.0, i_clamp_max: 1.0}
$(arg prefix)joint_7: {p: 100.0, i: 0.0, d: 0.0, i_clamp_min: -0.1, i_clamp_max: 0.1}

joint_1_position_controller:
joint: joint_1
$(arg prefix)joint_1_position_controller:
joint: $(arg prefix)joint_1
pid:
p: 3000.0
i: 0.0
d: 2.0
type: effort_controllers/JointPositionController

joint_2_position_controller:
joint: joint_2
$(arg prefix)joint_2_position_controller:
joint: $(arg prefix)joint_2
pid:
p: 50000.0
i: 0.0
d: 0.0
type: effort_controllers/JointPositionController

joint_3_position_controller:
joint: joint_3
$(arg prefix)joint_3_position_controller:
joint: $(arg prefix)joint_3
pid:
p: 3000.0
i: 0.0
d: 0.0
type: effort_controllers/JointPositionController

joint_4_position_controller:
joint: joint_4
$(arg prefix)joint_4_position_controller:
joint: $(arg prefix)joint_4
pid:
p: 50000.0
i: 0.0
d: 0.0
type: effort_controllers/JointPositionController

joint_5_position_controller:
joint: joint_5
$(arg prefix)joint_5_position_controller:
joint: $(arg prefix)joint_5
pid:
p: 750.0
i: 0.0
d: 0.2
type: effort_controllers/JointPositionController

joint_6_position_controller:
joint: joint_6
$(arg prefix)joint_6_position_controller:
joint: $(arg prefix)joint_6
pid:
p: 5000.0
i: 0.0
d: 1.0
type: effort_controllers/JointPositionController

joint_7_position_controller:
joint: joint_7
$(arg prefix)joint_7_position_controller:
joint: $(arg prefix)joint_7
pid:
p: 100.0
i: 0.0
Expand Down
Original file line number Diff line number Diff line change
@@ -1,73 +1,73 @@
# Publish all joint states -----------------------------------
joint_state_controller:
$(arg prefix)joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: 50

gen3_lite_joint_trajectory_controller:
$(arg prefix)gen3_lite_joint_trajectory_controller:
type: effort_controllers/JointTrajectoryController
joints:
- joint_1
- joint_2
- joint_3
- joint_4
- joint_5
- joint_6
- $(arg prefix)joint_1
- $(arg prefix)joint_2
- $(arg prefix)joint_3
- $(arg prefix)joint_4
- $(arg prefix)joint_5
- $(arg prefix)joint_6
constraints:
goal_time: 1.0
stopped_velocity_tolerance: 0.5
stop_trajectory_duration: 1.0
state_publish_rate: 25
action_monitor_rate: 25
gains:
joint_1: {p: 3000.0, i: 0.0, d: 2.0, i_clamp_min: -100.0, i_clamp_max: 100.0}
joint_2: {p: 50000.0, i: 0.0, d: 0.0, i_clamp_min: -5.0, i_clamp_max: 5.0}
joint_3: {p: 50000.0, i: 0.0, d: 0.0, i_clamp_min: -1.0, i_clamp_max: 1.0}
joint_4: {p: 750.0, i: 0.0, d: 0.2, i_clamp_min: -1.0, i_clamp_max: 1.0}
joint_5: {p: 5000.0, i: 0.0, d: 1.0, i_clamp_min: -1.0, i_clamp_max: 1.0}
joint_6: {p: 100.0, i: 0.0, d: 0.0, i_clamp_min: -0.1, i_clamp_max: 0.1}
$(arg prefix)joint_1: {p: 3000.0, i: 0.0, d: 2.0, i_clamp_min: -100.0, i_clamp_max: 100.0}
$(arg prefix)joint_2: {p: 50000.0, i: 0.0, d: 0.0, i_clamp_min: -5.0, i_clamp_max: 5.0}
$(arg prefix)joint_3: {p: 50000.0, i: 0.0, d: 0.0, i_clamp_min: -1.0, i_clamp_max: 1.0}
$(arg prefix)joint_4: {p: 750.0, i: 0.0, d: 0.2, i_clamp_min: -1.0, i_clamp_max: 1.0}
$(arg prefix)joint_5: {p: 5000.0, i: 0.0, d: 1.0, i_clamp_min: -1.0, i_clamp_max: 1.0}
$(arg prefix)joint_6: {p: 100.0, i: 0.0, d: 0.0, i_clamp_min: -0.1, i_clamp_max: 0.1}

joint_1_position_controller:
joint: joint_1
$(arg prefix)joint_1_position_controller:
joint: $(arg prefix)joint_1
pid:
p: 3000.0
i: 0.0
d: 2.0
type: effort_controllers/JointPositionController

joint_2_position_controller:
joint: joint_2
$(arg prefix)joint_2_position_controller:
joint: $(arg prefix)joint_2
pid:
p: 50000.0
i: 0.0
d: 0.0
type: effort_controllers/JointPositionController

joint_3_position_controller:
joint: joint_3
$(arg prefix)joint_3_position_controller:
joint: $(arg prefix)joint_3
pid:
p: 50000.0
i: 0.0
d: 0.0
type: effort_controllers/JointPositionController

joint_4_position_controller:
joint: joint_4
$(arg prefix)joint_4_position_controller:
joint: $(arg prefix)joint_4
pid:
p: 750.0
i: 0.0
d: 0.2
type: effort_controllers/JointPositionController

joint_5_position_controller:
joint: joint_5
$(arg prefix)joint_5_position_controller:
joint: $(arg prefix)joint_5
pid:
p: 5000.0
i: 0.0
d: 1.0
type: effort_controllers/JointPositionController

joint_6_position_controller:
joint: joint_6
$(arg prefix)joint_6_position_controller:
joint: $(arg prefix)joint_6
pid:
p: 100.0
i: 0.0
Expand Down
Original file line number Diff line number Diff line change
@@ -1,11 +1,11 @@
gen3_lite_2f_gripper_controller:
$(arg prefix)gen3_lite_2f_gripper_controller:
type: position_controllers/GripperActionController
joint: right_finger_bottom_joint
joint: $(arg prefix)right_finger_bottom_joint
action_monitor_rate: 100

gazebo_ros_control:
pid_gains:
right_finger_bottom_joint: {p: 0.1, i: 0.0, d: 0.0}
right_finger_tip_joint: {p: 1.0, i: 0.0, d: 0.0}
left_finger_bottom_joint: {p: 10.0, i: 0.0, d: 0.0}
left_finger_tip_joint: {p: 1.0, i: 0.0, d: 0.0}
$(arg prefix)right_finger_bottom_joint: {p: 10.0, i: 0.0, d: 0.0}
$(arg prefix)right_finger_tip_joint: {p: 1.0, i: 0.0, d: 0.0}
$(arg prefix)left_finger_bottom_joint: {p: 10.0, i: 0.0, d: 0.0}
$(arg prefix)left_finger_tip_joint: {p: 1.0, i: 0.0, d: 0.0}
Original file line number Diff line number Diff line change
@@ -1,13 +1,13 @@
robotiq_2f_140_gripper_controller:
$(arg prefix)robotiq_2f_140_gripper_controller:
type: position_controllers/GripperActionController
joint: finger_joint
joint: $(arg prefix)finger_joint
action_monitor_rate: 100

gazebo_ros_control:
pid_gains:
finger_joint: {p: 10.0, i: 0.0, d: 0.01}
right_outer_knuckle_joint: {p: 10.0, i: 0.0, d: 0.00}
right_inner_knuckle_joint: {p: 10.0, i: 0.0, d: 0.01}
left_inner_knuckle_joint: {p: 10.0, i: 0.0, d: 0.01}
left_inner_finger_joint: {p: 0.5, i: 0.0, d: 0.001}
right_inner_finger_joint: {p: 0.5, i: 0.0, d: 0.001}
$(arg prefix)finger_joint: {p: 10.0, i: 0.0, d: 0.01}
$(arg prefix)right_outer_knuckle_joint: {p: 10.0, i: 0.0, d: 0.00}
$(arg prefix)right_inner_knuckle_joint: {p: 10.0, i: 0.0, d: 0.01}
$(arg prefix)left_inner_knuckle_joint: {p: 10.0, i: 0.0, d: 0.01}
$(arg prefix)left_inner_finger_joint: {p: 0.5, i: 0.0, d: 0.001}
$(arg prefix)right_inner_finger_joint: {p: 0.5, i: 0.0, d: 0.001}
Original file line number Diff line number Diff line change
@@ -1,13 +1,13 @@
robotiq_2f_85_gripper_controller:
$(arg prefix)robotiq_2f_85_gripper_controller:
type: position_controllers/GripperActionController
joint: finger_joint
joint: $(arg prefix)finger_joint
action_monitor_rate: 100

gazebo_ros_control:
pid_gains:
finger_joint: {p: 10.0, i: 0.0, d: 0.01}
right_outer_knuckle_joint: {p: 10.0, i: 0.0, d: 0.00}
right_inner_knuckle_joint: {p: 10.0, i: 0.0, d: 0.01}
left_inner_knuckle_joint: {p: 10.0, i: 0.0, d: 0.01}
left_inner_finger_joint: {p: 0.5, i: 0.0, d: 0.001}
right_inner_finger_joint: {p: 0.5, i: 0.0, d: 0.001}
$(arg prefix)finger_joint: {p: 10.0, i: 0.0, d: 0.01}
$(arg prefix)right_outer_knuckle_joint: {p: 10.0, i: 0.0, d: 0.00}
$(arg prefix)right_inner_knuckle_joint: {p: 10.0, i: 0.0, d: 0.01}
$(arg prefix)left_inner_knuckle_joint: {p: 10.0, i: 0.0, d: 0.01}
$(arg prefix)left_inner_finger_joint: {p: 0.5, i: 0.0, d: 0.001}
$(arg prefix)right_inner_finger_joint: {p: 0.5, i: 0.0, d: 0.001}
Loading

0 comments on commit d2bf9e8

Please sign in to comment.