Public Member Functions | Private Attributes
OnlineJointTrajectoryFollower Class Reference

Provides a class for breadcrumbing an online trajectory. More...

#include <JointTrajectoryFollower.h>

Inheritance diagram for OnlineJointTrajectoryFollower:
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
 OnlineJointTrajectoryFollower ()
void setTrajectory (boost::shared_ptr< RosMsgJointTrajectory > trajectory_in, double timestep_in, double velocityFactor_in=1.)
 set trajectory
virtual ~OnlineJointTrajectoryFollower ()

Private Attributes

double time
double timestep
boost::shared_ptr
< RosMsgJointTrajectory
trajectory

Detailed Description

Provides a class for breadcrumbing an online trajectory.

Definition at line 100 of file JointTrajectoryFollower.h.


Constructor & Destructor Documentation

Definition at line 202 of file JointTrajectoryFollower.cpp.

Definition at line 104 of file JointTrajectoryFollower.h.


Member Function Documentation

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

Implements JointTrajectoryFollower.

Definition at line 108 of file JointTrajectoryFollower.h.

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

Implements JointTrajectoryFollower.

Definition at line 106 of file JointTrajectoryFollower.h.

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

get next point

Get the next point in the trajectory for the online 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

Implements JointTrajectoryFollower.

Definition at line 244 of file JointTrajectoryFollower.cpp.

void OnlineJointTrajectoryFollower::setTrajectory ( boost::shared_ptr< RosMsgJointTrajectory trajectoryIn,
double  timestep_in,
double  velocityFactorIn = 1. 
)

set trajectory

Set trajectory, velocity factor, and time step increments for an online joint.

Parameters:
trajectory_innew trajectory
Returns:
void

if there is an existing trajectory, it is preempted

Parameters:
trajectoryIn
timestep_in
velocityFactorIn
Exceptions:
runtime_errorIf joint is currently following a trajectory

Definition at line 215 of file JointTrajectoryFollower.cpp.


Member Data Documentation

Definition at line 128 of file JointTrajectoryFollower.h.

Definition at line 128 of file JointTrajectoryFollower.h.

Definition at line 127 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