Public Member Functions | Public Attributes
JointTrajectoryFollower Class Reference

Provides a an abstract class for breadcrumbing a trajectory and maintaining status. More...

#include <JointTrajectoryFollower.h>

Inheritance diagram for JointTrajectoryFollower:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual void abort (const std::string &msg=std::string())
 abort stops trajectory and sets status to aborted
virtual double getDuration () const =0
virtual const std::vector
< std::string > & 
getJointNames () const =0
virtual void getNextPoint (sensor_msgs::JointState &nextPoint, ros::Duration &timeFromStart)=0
 get next point
virtual bool isActive () const
 isActive
 JointTrajectoryFollower ()
 Constructor for Joint Trajectory Follower.
virtual void preempt (const std::string &msg=std::string())
 preempt stops trajectory and sets status to preempted
virtual ~JointTrajectoryFollower ()

Public Attributes

GoalManager goalManager
double velocityFactor

Detailed Description

Provides a an abstract class for breadcrumbing a trajectory and maintaining status.

Definition at line 21 of file JointTrajectoryFollower.h.


Constructor & Destructor Documentation

Constructor for Joint Trajectory Follower.

Definition at line 9 of file JointTrajectoryFollower.cpp.

Definition at line 25 of file JointTrajectoryFollower.h.


Member Function Documentation

void JointTrajectoryFollower::abort ( const std::string &  msg = std::string()) [virtual]

abort stops trajectory and sets status to aborted

Set Ready State to false and abort Joint Trajectory Follower.

Definition at line 19 of file JointTrajectoryFollower.cpp.

virtual double JointTrajectoryFollower::getDuration ( ) const [pure virtual]
virtual const std::vector<std::string>& JointTrajectoryFollower::getJointNames ( ) const [pure virtual]
virtual void JointTrajectoryFollower::getNextPoint ( sensor_msgs::JointState &  nextPoint,
ros::Duration timeFromStart 
) [pure virtual]

get next point

Parameters:
nextPointjoint state of next point, returned
timeFromStarttime from start of next point, returned
Returns:
void

Implemented in OnlineJointTrajectoryFollower, and PreplannedJointTrajectoryFollower.

virtual bool JointTrajectoryFollower::isActive ( ) const [inline, virtual]

isActive

Returns:
bool active state

false if done with trajectory or reset, true otherwise

Definition at line 36 of file JointTrajectoryFollower.h.

void JointTrajectoryFollower::preempt ( const std::string &  msg = std::string()) [virtual]

preempt stops trajectory and sets status to preempted

Set Ready State to false and preempt Joint Trajectory Follower.

Definition at line 30 of file JointTrajectoryFollower.cpp.


Member Data Documentation

Definition at line 55 of file JointTrajectoryFollower.h.

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