Public Member Functions | Protected Types | Protected Attributes | Private Attributes
RosMsgForceTrajectoryFactory Class Reference

#include <RosMsgForceTrajectoryFactory.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 r2_msgs::ForceControlAxisArray &forceControlAxes) const
 getTrajectory produces a trajectory object from the inputs
 RosMsgForceTrajectoryFactory ()
void setCartesianFactory (boost::shared_ptr< const SynchedCartesianTrajectoryFactory > factory_in)
void setForceController (boost::shared_ptr< Cartesian_HybCntrl > forceController_in)
void setTreeIk (boost::shared_ptr< KdlTreeIk > treeIk_in)
virtual ~RosMsgForceTrajectoryFactory ()

Protected Types

typedef
CartesianTrajectorySequenceFactory
< SynchedTrajectory
sequenceFactoryType

Protected Attributes

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

Private Attributes

const std::string logCategory

Detailed Description

Definition at line 18 of file RosMsgForceTrajectoryFactory.h.


Member Typedef Documentation

Definition at line 65 of file RosMsgForceTrajectoryFactory.h.


Constructor & Destructor Documentation

Definition at line 3 of file RosMsgForceTrajectoryFactory.cpp.

Definition at line 22 of file RosMsgForceTrajectoryFactory.h.


Member Function Documentation

boost::shared_ptr< RosMsgJointTrajectory > RosMsgForceTrajectoryFactory::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 r2_msgs::ForceControlAxisArray &  forceControlAxes 
) 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 8 of file RosMsgForceTrajectoryFactory.cpp.

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

Definition at line 24 of file RosMsgForceTrajectoryFactory.h.

void RosMsgForceTrajectoryFactory::setForceController ( boost::shared_ptr< Cartesian_HybCntrl forceController_in) [inline]

Definition at line 37 of file RosMsgForceTrajectoryFactory.h.

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

Definition at line 31 of file RosMsgForceTrajectoryFactory.h.


Member Data Documentation

Definition at line 67 of file RosMsgForceTrajectoryFactory.h.

Definition at line 63 of file RosMsgForceTrajectoryFactory.h.

const std::string RosMsgForceTrajectoryFactory::logCategory [private]

Definition at line 69 of file RosMsgForceTrajectoryFactory.h.

Definition at line 66 of file RosMsgForceTrajectoryFactory.h.

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

Definition at line 61 of file RosMsgForceTrajectoryFactory.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