Public Member Functions | Private Attributes
PreplannedJointTrajectoryFollower Class Reference

Provides a class for breadcrumbing a preplanned trajectory. More...

#include <JointTrajectoryFollower.h>

Inheritance diagram for PreplannedJointTrajectoryFollower:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual double getDuration () const
virtual const std::vector
< std::string > & 
getJointNames () const
virtual void getNextPoint (sensor_msgs::JointState &nextPoint, ros::Duration &timeFromStart)
 get next point
 PreplannedJointTrajectoryFollower ()
void setTrajectory (const trajectory_msgs::JointTrajectory &trajectory_in, double timestep_in=0.03333, double velocityFactor_in=1.)
 set trajectory
virtual ~PreplannedJointTrajectoryFollower ()

Private Attributes

double currentTrajCount
double timestep
trajectory_msgs::JointTrajectory trajectory
trajectory_msgs::JointTrajectory::_points_type::const_iterator trajIt

Detailed Description

Provides a class for breadcrumbing a preplanned trajectory.

Definition at line 63 of file JointTrajectoryFollower.h.


Constructor & Destructor Documentation

Definition at line 41 of file JointTrajectoryFollower.cpp.

Definition at line 67 of file JointTrajectoryFollower.h.


Member Function Documentation

virtual double PreplannedJointTrajectoryFollower::getDuration ( ) const [inline, virtual]

Implements JointTrajectoryFollower.

Definition at line 71 of file JointTrajectoryFollower.h.

virtual const std::vector<std::string>& PreplannedJointTrajectoryFollower::getJointNames ( ) const [inline, virtual]

Implements JointTrajectoryFollower.

Definition at line 69 of file JointTrajectoryFollower.h.

void PreplannedJointTrajectoryFollower::getNextPoint ( sensor_msgs::JointState &  nextPoint,
ros::Duration timeFromStart 
) [virtual]

get next point

Get the next point in the trajectory for the preplanned joint.

Parameters:
nextPointjoint state of next point, returned
timeFromStarttime from start of next point, returned
Returns:
void
Parameters:
nextPointNext joint state
timeFromStartTime from the start of beginning of trajectory
Exceptions:
runtime_errorIf trajectory is inactive, or if trajectory names, positions, velocities, accelerations are not properly sized

Implements JointTrajectoryFollower.

Definition at line 101 of file JointTrajectoryFollower.cpp.

void PreplannedJointTrajectoryFollower::setTrajectory ( const trajectory_msgs::JointTrajectory trajectoryIn,
double  timestep_in = 0.03333,
double  velocityFactorIn = 1. 
)

set trajectory

Set trajectory and velocity to new values and prepare preplanned joint for new trajectory.

Parameters:
trajectory_innew trajectory
Returns:
void

if there is an existing trajectory, it is preempted

Parameters:
trajectoryInNew trajectory value for joint
velocityFactorInNew velocity factor value for joint
Exceptions:
runtime_errorIf Joint is already following a trajectory

Definition at line 53 of file JointTrajectoryFollower.cpp.


Member Data Documentation

Definition at line 92 of file JointTrajectoryFollower.h.

Definition at line 93 of file JointTrajectoryFollower.h.

Definition at line 90 of file JointTrajectoryFollower.h.

trajectory_msgs::JointTrajectory::_points_type::const_iterator PreplannedJointTrajectoryFollower::trajIt [private]

Definition at line 91 of file JointTrajectoryFollower.h.


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


robodyn_controllers
Author(s):
autogenerated on Sat Jun 8 2019 20:20:54