Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Switch to velocity controllers to overcome bug from position controllers #5

Merged
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
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}