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

#include <RosMsgTreeIkTrajectoryFactory.h>

List of all members.

Public Member Functions

virtual boost::shared_ptr
< RosMsgJointTrajectory
getTrajectory (const sensor_msgs::JointState &jointPositions, const sensor_msgs::JointState &jointVels, const sensor_msgs::JointState &prevJointVels, const r2_msgs::PoseState &poseState, const r2_msgs::PoseState &poseVels, const r2_msgs::PoseTrajectory &goalTraj) const
 getTrajectory produces a trajectory object from the inputs
 RosMsgTreeIkTrajectoryFactory ()
void setCartesianFactory (boost::shared_ptr< const SynchedCartesianTrajectoryFactory > factory_in)
void setTreeIk (boost::shared_ptr< KdlTreeIk > treeIk_in)
virtual ~RosMsgTreeIkTrajectoryFactory ()

Protected Types

typedef
CartesianTrajectorySequenceFactory
< SynchedTrajectory
sequenceFactoryType

Protected Attributes

boost::shared_ptr< const
SynchedCartesianTrajectoryFactory
factory
boost::shared_ptr
< sequenceFactoryType
sequenceFactory
boost::shared_ptr< KdlTreeIktreeIk

Detailed Description

Definition at line 23 of file RosMsgTreeIkTrajectoryFactory.h.


Member Typedef Documentation

Definition at line 60 of file RosMsgTreeIkTrajectoryFactory.h.


Constructor & Destructor Documentation

Definition at line 26 of file RosMsgTreeIkTrajectoryFactory.h.

Definition at line 27 of file RosMsgTreeIkTrajectoryFactory.h.


Member Function Documentation

boost::shared_ptr< RosMsgJointTrajectory > RosMsgTreeIkTrajectoryFactory::getTrajectory ( const sensor_msgs::JointState &  jointPositions,
const sensor_msgs::JointState &  jointVels,
const sensor_msgs::JointState &  prevJointVels,
const r2_msgs::PoseState &  poseState,
const r2_msgs::PoseState &  poseVels,
const r2_msgs::PoseTrajectory &  goalTraj 
) const [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)
poseStatestart cartesian poses
poseVelsstarting cartesian vels
goalTrajgoal joint positions

Definition at line 3 of file RosMsgTreeIkTrajectoryFactory.cpp.

void RosMsgTreeIkTrajectoryFactory::setCartesianFactory ( boost::shared_ptr< const SynchedCartesianTrajectoryFactory factory_in) [inline]

Definition at line 29 of file RosMsgTreeIkTrajectoryFactory.h.

void RosMsgTreeIkTrajectoryFactory::setTreeIk ( boost::shared_ptr< KdlTreeIk treeIk_in) [inline]

Definition at line 36 of file RosMsgTreeIkTrajectoryFactory.h.


Member Data Documentation

Definition at line 62 of file RosMsgTreeIkTrajectoryFactory.h.

Definition at line 61 of file RosMsgTreeIkTrajectoryFactory.h.

boost::shared_ptr<KdlTreeIk> RosMsgTreeIkTrajectoryFactory::treeIk [protected]

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