Skip to content

Commit

Permalink
Merge pull request #5 from sleong1/simulation_that_works
Browse files Browse the repository at this point in the history
Switch to velocity controllers to overcome bug from position controllers
  • Loading branch information
awesomebytes authored Jan 18, 2019
2 parents dd497b6 + c1297ea commit e3ce91e
Showing 1 changed file with 73 additions and 73 deletions.
146 changes: 73 additions & 73 deletions pepper_control/config/pepper_trajectory_control.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -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:
Expand Down Expand Up @@ -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}


0 comments on commit e3ce91e

Please sign in to comment.