diff --git a/pepper_control/config/pepper_trajectory_control.yaml b/pepper_control/config/pepper_trajectory_control.yaml index c42f6c8..9aa9864 100644 --- a/pepper_control/config/pepper_trajectory_control.yaml +++ b/pepper_control/config/pepper_trajectory_control.yaml @@ -5,33 +5,33 @@ pepper: publish_rate: 50 # Controllers ------------------------------------------------ - LeftArm_controller: - type: position_controllers/JointTrajectoryController - joints: - - LShoulderPitch - - LShoulderRoll - - LElbowYaw - - LElbowRoll - - LWristYaw - RightArm_controller: - type: position_controllers/JointTrajectoryController - joints: - - RShoulderPitch - - RShoulderRoll - - RElbowYaw - - RElbowRoll - - RWristYaw - Head_controller: - type: position_controllers/JointTrajectoryController - joints: - - HeadYaw - - HeadPitch - Pelvis_controller: - type: position_controllers/JointTrajectoryController - joints: - - HipRoll - - HipPitch - - KneePitch + # LeftArm_controller: + # type: position_controllers/JointTrajectoryController + # joints: + # - LShoulderPitch + # - LShoulderRoll + # - LElbowYaw + # - LElbowRoll + # - LWristYaw + # RightArm_controller: + # type: position_controllers/JointTrajectoryController + # joints: + # - RShoulderPitch + # - RShoulderRoll + # - RElbowYaw + # - RElbowRoll + # - RWristYaw + # Head_controller: + # type: position_controllers/JointTrajectoryController + # joints: + # - HeadYaw + # - HeadPitch + # Pelvis_controller: + # type: position_controllers/JointTrajectoryController + # joints: + # - HipRoll + # - HipPitch + # - KneePitch # LeftHand_controller: # type: position_controllers/JointTrajectoryController # joints: @@ -75,51 +75,51 @@ pepper: - # LeftArm_controller: - # type: velocity_controllers/JointTrajectoryController - # joints: - # - LShoulderPitch - # - LShoulderRoll - # - LElbowYaw - # - LElbowRoll - # - LWristYaw - # gains: - # LShoulderPitch: {p: 1000.0, i: 0.01, d: 10.0} - # LShoulderRoll: {p: 1000.0, i: 0.01, d: 10.0} - # LElbowYaw: {p: 1000.0, i: 0.01, d: 10.0} - # LElbowRoll: {p: 1000.0, i: 0.01, d: 10.0} - # LWristYaw: {p: 1000.0, i: 0.01, d: 10.0} - # RightArm_controller: - # type: velocity_controllers/JointTrajectoryController - # joints: - # - RShoulderPitch - # - RShoulderRoll - # - RElbowYaw - # - RElbowRoll - # - RWristYaw - # gains: - # RShoulderPitch: {p: 1000.0, i: 0.01, d: 10.0} - # RShoulderRoll: {p: 1000.0, i: 0.01, d: 10.0} - # RElbowYaw: {p: 1000.0, i: 0.01, d: 10.0} - # RElbowRoll: {p: 1000.0, i: 0.01, d: 10.0} - # RWristYaw: {p: 1000.0, i: 0.01, d: 10.0} - # Head_controller: - # type: velocity_controllers/JointTrajectoryController - # joints: - # - HeadYaw - # - HeadPitch - # gains: - # HeadYaw: {p: 1000.0, i: 0.01, d: 10.0} - # HeadPitch: {p: 1000.0, i: 0.01, d: 10.0} - # Pelvis_controller: - # type: velocity_controllers/JointTrajectoryController - # joints: - # - HipRoll - # - HipPitch - # - KneePitch - # gains: - # HipRoll: {p: 1000.0, i: 0.01, d: 10.0} - # HipPitch: {p: 1000.0, i: 0.01, d: 10.0} - # KneePitch: {p: 1000.0, i: 0.01, d: 10.0} + LeftArm_controller: + type: velocity_controllers/JointTrajectoryController + joints: + - LShoulderPitch + - LShoulderRoll + - LElbowYaw + - LElbowRoll + - LWristYaw + gains: + LShoulderPitch: {p: 1000.0, i: 0.01, d: 10.0} + LShoulderRoll: {p: 1000.0, i: 0.01, d: 10.0} + LElbowYaw: {p: 1000.0, i: 0.01, d: 10.0} + LElbowRoll: {p: 1000.0, i: 0.01, d: 10.0} + LWristYaw: {p: 1000.0, i: 0.01, d: 10.0} + RightArm_controller: + type: velocity_controllers/JointTrajectoryController + joints: + - RShoulderPitch + - RShoulderRoll + - RElbowYaw + - RElbowRoll + - RWristYaw + gains: + RShoulderPitch: {p: 1000.0, i: 0.01, d: 10.0} + RShoulderRoll: {p: 1000.0, i: 0.01, d: 10.0} + RElbowYaw: {p: 1000.0, i: 0.01, d: 10.0} + RElbowRoll: {p: 1000.0, i: 0.01, d: 10.0} + RWristYaw: {p: 1000.0, i: 0.01, d: 10.0} + Head_controller: + type: velocity_controllers/JointTrajectoryController + joints: + - HeadYaw + - HeadPitch + gains: + HeadYaw: {p: 1000.0, i: 0.01, d: 10.0} + HeadPitch: {p: 1000.0, i: 0.01, d: 10.0} + Pelvis_controller: + type: velocity_controllers/JointTrajectoryController + joints: + - HipRoll + - HipPitch + - KneePitch + gains: + HipRoll: {p: 1000.0, i: 0.01, d: 10.0} + HipPitch: {p: 1000.0, i: 0.01, d: 10.0} + KneePitch: {p: 1000.0, i: 0.01, d: 10.0}