Public Member Functions | Protected Types | Protected Attributes
RosMsgJointTrajectoryFactory Class Reference

#include <RosMsgTrajectoryFactory.h>

List of all members.

Public Member Functions

void getSettings (r2_msgs::ControllerJointSettings &settings)
virtual boost::shared_ptr
< RosMsgJointTrajectory
getTrajectory (const sensor_msgs::JointState &jointPositions, const sensor_msgs::JointState &jointVels, const sensor_msgs::JointState &prevJointVels, const trajectory_msgs::JointTrajectory &goalTraj)
 getTrajectory produces a trajectory object from the inputs
 RosMsgJointTrajectoryFactory ()
void setFactory (boost::shared_ptr< JointTrajectoryFactory<> > factory_in)
void setLimits (const std::vector< std::string > &jointNames, double velLim, double accLim)
void setPositionLimiter (boost::shared_ptr< JointNamePositionLimiter > posLimiter)
void setSettings (const r2_msgs::ControllerJointSettings &settings)
virtual ~RosMsgJointTrajectoryFactory ()

Protected Types

typedef
JointTrajectorySequenceFactory 
sequenceFactoryType

Protected Attributes

boost::shared_ptr
< JointTrajectoryFactory<> > 
factory
JointNameMotionLimiter motionLimiter
boost::shared_ptr
< JointNamePositionLimiter
positionLimiter
sequenceFactoryType sequenceFactory

Detailed Description

Definition at line 26 of file RosMsgTrajectoryFactory.h.


Member Typedef Documentation

Definition at line 57 of file RosMsgTrajectoryFactory.h.


Constructor & Destructor Documentation

Definition at line 29 of file RosMsgTrajectoryFactory.h.

Definition at line 30 of file RosMsgTrajectoryFactory.h.


Member Function Documentation

void RosMsgJointTrajectoryFactory::getSettings ( r2_msgs::ControllerJointSettings &  settings)

Definition at line 10 of file RosMsgTrajectoryFactory.cpp.

boost::shared_ptr< RosMsgJointTrajectory > RosMsgJointTrajectoryFactory::getTrajectory ( const sensor_msgs::JointState &  jointPositions,
const sensor_msgs::JointState &  jointVels,
const sensor_msgs::JointState &  prevJointVels,
const trajectory_msgs::JointTrajectory goalTraj 
) [virtual]

getTrajectory produces a trajectory object from the inputs

Parameters:
jointPositionsstart joint positions
jointVelsstart joint velocities
prevJointVelsprevious joint velocities (joint states only hold pos & vel so the prev is used to derive acc)
goalTrajgoal joint positions
Todo:
this may limit wrists too much

if position limited, set vel and acc to 0

also set acceleration limit higher if needed

Definition at line 25 of file RosMsgTrajectoryFactory.cpp.

void RosMsgJointTrajectoryFactory::setFactory ( boost::shared_ptr< JointTrajectoryFactory<> >  factory_in) [inline]

Definition at line 32 of file RosMsgTrajectoryFactory.h.

void RosMsgJointTrajectoryFactory::setLimits ( const std::vector< std::string > &  jointNames,
double  velLim,
double  accLim 
)

Definition at line 15 of file RosMsgTrajectoryFactory.cpp.

Definition at line 20 of file RosMsgTrajectoryFactory.cpp.

void RosMsgJointTrajectoryFactory::setSettings ( const r2_msgs::ControllerJointSettings &  settings)

Definition at line 5 of file RosMsgTrajectoryFactory.cpp.


Member Data Documentation

Definition at line 59 of file RosMsgTrajectoryFactory.h.

Definition at line 60 of file RosMsgTrajectoryFactory.h.

Definition at line 61 of file RosMsgTrajectoryFactory.h.

Definition at line 58 of file RosMsgTrajectoryFactory.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