Public Member Functions | Private Member Functions | Private Attributes
JointTrajectoryAction Class Reference

#include <joint_trajectory_action.h>

List of all members.

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
JointStateObserverjointStateObserver
double positionGain
double velocityGain

Detailed Description

Definition at line 60 of file joint_trajectory_action.h.


Constructor & Destructor Documentation

Definition at line 60 of file joint_trajectory_action.cpp.

JointTrajectoryAction::JointTrajectoryAction ( JointStateObserver youbot,
double  velocityGain,
double  positionGain,
double  frequency 
)

Definition at line 70 of file joint_trajectory_action.cpp.

Definition at line 83 of file joint_trajectory_action.cpp.

Definition at line 91 of file joint_trajectory_action.cpp.


Member Function Documentation

double JointTrajectoryAction::calculateVelocity ( double  actualAngle,
double  actualVelocity,
const KDL::Trajectory_Composite &  trajectoryComposite,
double  elapsedTimeInSec 
) [private]

Definition at line 126 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 152 of file joint_trajectory_action.cpp.

void JointTrajectoryAction::execute ( const control_msgs::FollowJointTrajectoryGoalConstPtr &  goal,
Server as 
)

Definition at line 195 of file joint_trajectory_action.cpp.

Definition at line 101 of file joint_trajectory_action.cpp.

Definition at line 121 of file joint_trajectory_action.cpp.

Definition at line 111 of file joint_trajectory_action.cpp.

void JointTrajectoryAction::jointStateCallback ( const sensor_msgs::JointState &  joint_state)

Definition at line 290 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 96 of file joint_trajectory_action.cpp.

void JointTrajectoryAction::setPositionGain ( double  positionGain)

Definition at line 116 of file joint_trajectory_action.cpp.

void JointTrajectoryAction::setTargetTrajectory ( double  angle1,
double  angle2,
double  duration,
KDL::Trajectory_Composite &  trajectoryComposite 
) [private]

Definition at line 176 of file joint_trajectory_action.cpp.

void JointTrajectoryAction::setVelocityGain ( double  velocityGain)

Definition at line 106 of file joint_trajectory_action.cpp.


Member Data Documentation

sensor_msgs::JointState JointTrajectoryAction::current_state [private]

Definition at line 93 of file joint_trajectory_action.h.

Definition at line 91 of file joint_trajectory_action.h.

Definition at line 94 of file joint_trajectory_action.h.

Definition at line 90 of file joint_trajectory_action.h.

Definition at line 89 of file joint_trajectory_action.h.


The documentation for this class was generated from the following files:


youbot_driver_ros_interface
Author(s): Sebastian Blumenthal
autogenerated on Thu Jun 6 2019 20:43:35