#include <joint_trajectory_action.h>
Public Member Functions | |
void | execute (const control_msgs::FollowJointTrajectoryGoalConstPtr &goal, Server *as) |
double | getFrequency () const |
double | getPositionGain () const |
double | getVelocityGain () const |
void | jointStateCallback (const sensor_msgs::JointState &joint_state) |
void | jointStateCallback (const brics_actuator::JointPositions &position, const brics_actuator::JointVelocities &velocity) |
JointTrajectoryAction (JointStateObserver *jointStateObserver) | |
JointTrajectoryAction (JointStateObserver *youbot, double velocityGain, double positionGain, double frequency) | |
JointTrajectoryAction (const JointTrajectoryAction &orig) | |
void | setFrequency (double frequency) |
void | setPositionGain (double positionGain) |
void | setVelocityGain (double velocityGain) |
virtual | ~JointTrajectoryAction () |
Private Member Functions | |
double | calculateVelocity (double actualAngle, double actualVelocity, const KDL::Trajectory_Composite &trajectoryComposite, double elapsedTimeInSec) |
void | controlLoop (const std::vector< double > &actualJointAngles, const std::vector< double > &actualJointVelocities, const KDL::Trajectory_Composite *trajectoryComposite, int numberOfJoints, ros::Time startTime, std::vector< double > &velocities) |
void | setTargetTrajectory (double angle1, double angle2, double duration, KDL::Trajectory_Composite &trajectoryComposite) |
Private Attributes | |
sensor_msgs::JointState | current_state |
double | frequency |
JointStateObserver * | jointStateObserver |
double | positionGain |
double | velocityGain |
Definition at line 59 of file joint_trajectory_action.h.
JointTrajectoryAction::JointTrajectoryAction | ( | JointStateObserver * | jointStateObserver | ) |
Definition at line 58 of file joint_trajectory_action.cpp.
JointTrajectoryAction::JointTrajectoryAction | ( | JointStateObserver * | youbot, |
double | velocityGain, | ||
double | positionGain, | ||
double | frequency | ||
) |
Definition at line 68 of file joint_trajectory_action.cpp.
JointTrajectoryAction::JointTrajectoryAction | ( | const JointTrajectoryAction & | orig | ) |
Definition at line 79 of file joint_trajectory_action.cpp.
JointTrajectoryAction::~JointTrajectoryAction | ( | ) | [virtual] |
Definition at line 88 of file joint_trajectory_action.cpp.
double JointTrajectoryAction::calculateVelocity | ( | double | actualAngle, |
double | actualVelocity, | ||
const KDL::Trajectory_Composite & | trajectoryComposite, | ||
double | elapsedTimeInSec | ||
) | [private] |
Definition at line 123 of file joint_trajectory_action.cpp.
void JointTrajectoryAction::controlLoop | ( | const std::vector< double > & | actualJointAngles, |
const std::vector< double > & | actualJointVelocities, | ||
const KDL::Trajectory_Composite * | trajectoryComposite, | ||
int | numberOfJoints, | ||
ros::Time | startTime, | ||
std::vector< double > & | velocities | ||
) | [private] |
Definition at line 148 of file joint_trajectory_action.cpp.
void JointTrajectoryAction::execute | ( | const control_msgs::FollowJointTrajectoryGoalConstPtr & | goal, |
Server * | as | ||
) |
Definition at line 184 of file joint_trajectory_action.cpp.
double JointTrajectoryAction::getFrequency | ( | ) | const |
Definition at line 98 of file joint_trajectory_action.cpp.
double JointTrajectoryAction::getPositionGain | ( | ) | const |
Definition at line 118 of file joint_trajectory_action.cpp.
double JointTrajectoryAction::getVelocityGain | ( | ) | const |
Definition at line 108 of file joint_trajectory_action.cpp.
void JointTrajectoryAction::jointStateCallback | ( | const sensor_msgs::JointState & | joint_state | ) |
Definition at line 272 of file joint_trajectory_action.cpp.
void JointTrajectoryAction::jointStateCallback | ( | const brics_actuator::JointPositions & | position, |
const brics_actuator::JointVelocities & | velocity | ||
) |
void JointTrajectoryAction::setFrequency | ( | double | frequency | ) |
Definition at line 93 of file joint_trajectory_action.cpp.
void JointTrajectoryAction::setPositionGain | ( | double | positionGain | ) |
Definition at line 113 of file joint_trajectory_action.cpp.
void JointTrajectoryAction::setTargetTrajectory | ( | double | angle1, |
double | angle2, | ||
double | duration, | ||
KDL::Trajectory_Composite & | trajectoryComposite | ||
) | [private] |
Definition at line 168 of file joint_trajectory_action.cpp.
void JointTrajectoryAction::setVelocityGain | ( | double | velocityGain | ) |
Definition at line 103 of file joint_trajectory_action.cpp.
sensor_msgs::JointState JointTrajectoryAction::current_state [private] |
Definition at line 88 of file joint_trajectory_action.h.
double JointTrajectoryAction::frequency [private] |
Definition at line 86 of file joint_trajectory_action.h.
Definition at line 89 of file joint_trajectory_action.h.
double JointTrajectoryAction::positionGain [private] |
Definition at line 85 of file joint_trajectory_action.h.
double JointTrajectoryAction::velocityGain [private] |
Definition at line 84 of file joint_trajectory_action.h.