Public Member Functions | Protected Member Functions | Private Attributes
R2RosTrajectoryManager Class Reference

#include <R2RosTrajectoryManager.hpp>

List of all members.

Public Member Functions

void basesCallback (const r2_msgs::StringArray &msg)
r2_msgs::JointControlDataArray fromJointCommandToJointControl (const r2_msgs::JointCommand &jointCommandMsg)
sensor_msgs::JointState fromJointCommandToJointState (const r2_msgs::JointCommand &jointCommandMsg)
void inertiaCallback (const sensor_msgs::JointState &msg)
void jointCapabilitiesCallback (const r2_msgs::JointCapability &msg)
void jointCommandCallback (const r2_msgs::JointCommand &msg)
void jointRefsCallback (const r2_msgs::JointTrajectoryReplan &msg)
void jointSettingsCallback (const r2_msgs::ControllerJointSettings &msg)
void jointStatesCallback (const sensor_msgs::JointState &msg)
void jointTrajCallback (const trajectory_msgs::JointTrajectory &msg)
void poseCommandCallback (const r2_msgs::PoseState &msg)
void poseRefsCallback (const r2_msgs::PoseTrajectoryReplan &msg)
void poseSettingsCallback (const r2_msgs::ControllerPoseSettings &msg)
void poseStatesCallback (const r2_msgs::PoseState &msg)
void poseWaitCallback (const ros::TimerEvent &event)
 R2RosTrajectoryManager (const std::string name, const std::string &urdf, const double &timestep, ros::NodeHandle &nh)
void setCartesianParameters (std::vector< double > priorityNum, std::vector< double > linearTol, std::vector< double > angularTol, double momLimit, double taskGain, int ikMaxItr, double ikMaxTwist)
void update ()
virtual ~R2RosTrajectoryManager ()

Protected Member Functions

virtual void writeJointControl (const r2_msgs::JointControlDataArray &jointControl_out)
virtual void writeJointState (const sensor_msgs::JointState &jointState_out)
virtual void writeStatus (const actionlib_msgs::GoalStatusArray &goalStatusMsg_out)

Private Attributes

ros::Subscriber basesIn
ros::Publisher goalStatusOut
ros::Subscriber inertiaIn
ros::Subscriber jointCapabilitiesIn
ros::Publisher jointCommandOut
 publishers and subscribers
sensor_msgs::JointState jointCommandOutMsg
ros::Subscriber jointCommandRefsIn
r2_msgs::JointCommand jointCommandsMsg
ros::Subscriber jointRefsIn
r2_msgs::JointTrajectoryReplan jointRefsMsg
ros::Subscriber jointSettingsIn
r2_msgs::ControllerJointSettings jointSettingsMsg
 messages
ros::Publisher jointSettingsOut
ros::Subscriber jointStatesIn
sensor_msgs::JointState jointStatesMsg
r2_msgs::JointControlDataArray jointStatusMsg
ros::Subscriber jointTrajIn
ros::NodeHandle nh
ros::Publisher poseCommandOut
r2_msgs::PoseState poseCommandOutMsg
ros::Subscriber poseCommandRefIn
r2_msgs::PoseState poseCommandsMsg
ros::Subscriber poseRefsIn
r2_msgs::PoseTrajectoryReplan poseRefsMsg
ros::Publisher poseRefsOut
std::queue
< r2_msgs::PoseTrajectoryReplan > 
poseRefsQueue
ros::Subscriber poseSettingsIn
ros::Subscriber poseStatesIn
ros::Publisher poseStatesOut
r2_msgs::PoseState poseStatesOutMsg
r2_msgs::JointCommand prevJointCommandsMsg
sensor_msgs::JointState prevJointStatesMsg
double replanHoldAccelerationLimit
double replanHoldVelocityLimit
r2_msgs::ControllerJointSettings replanJointSettings
double replanSettingsVelocityCutoff
double replanStopAccelerationLimit
double replanStopVelocityLimit
double timeStepProp
trajectory_msgs::JointTrajectory trajInMsg
RosMsgTreeFk treeFk
std::string urdfFile
double waitForKasquish

Detailed Description

Definition at line 16 of file R2RosTrajectoryManager.hpp.


Constructor & Destructor Documentation

R2RosTrajectoryManager::R2RosTrajectoryManager ( const std::string  name,
const std::string &  urdf,
const double &  timestep,
ros::NodeHandle nh 
)

publishers and subscribers

Definition at line 3 of file R2RosTrajectoryManager.cpp.

virtual R2RosTrajectoryManager::~R2RosTrajectoryManager ( ) [inline, virtual]

Definition at line 20 of file R2RosTrajectoryManager.hpp.


Member Function Documentation

void R2RosTrajectoryManager::basesCallback ( const r2_msgs::StringArray &  msg)

Definition at line 110 of file R2RosTrajectoryManager.cpp.

r2_msgs::JointControlDataArray R2RosTrajectoryManager::fromJointCommandToJointControl ( const r2_msgs::JointCommand &  jointCommandMsg)

Definition at line 204 of file R2RosTrajectoryManager.cpp.

sensor_msgs::JointState R2RosTrajectoryManager::fromJointCommandToJointState ( const r2_msgs::JointCommand &  jointCommandMsg)

Definition at line 191 of file R2RosTrajectoryManager.cpp.

void R2RosTrajectoryManager::inertiaCallback ( const sensor_msgs::JointState &  msg)

Definition at line 116 of file R2RosTrajectoryManager.cpp.

void R2RosTrajectoryManager::jointCapabilitiesCallback ( const r2_msgs::JointCapability &  msg)

Definition at line 73 of file R2RosTrajectoryManager.cpp.

void R2RosTrajectoryManager::jointCommandCallback ( const r2_msgs::JointCommand &  msg)

Definition at line 55 of file R2RosTrajectoryManager.cpp.

void R2RosTrajectoryManager::jointRefsCallback ( const r2_msgs::JointTrajectoryReplan &  msg)

Definition at line 79 of file R2RosTrajectoryManager.cpp.

void R2RosTrajectoryManager::jointSettingsCallback ( const r2_msgs::ControllerJointSettings &  msg)

Definition at line 47 of file R2RosTrajectoryManager.cpp.

void R2RosTrajectoryManager::jointStatesCallback ( const sensor_msgs::JointState &  msg)

Definition at line 64 of file R2RosTrajectoryManager.cpp.

void R2RosTrajectoryManager::jointTrajCallback ( const trajectory_msgs::JointTrajectory &  msg)

Definition at line 95 of file R2RosTrajectoryManager.cpp.

void R2RosTrajectoryManager::poseCommandCallback ( const r2_msgs::PoseState &  msg)

Definition at line 134 of file R2RosTrajectoryManager.cpp.

void R2RosTrajectoryManager::poseRefsCallback ( const r2_msgs::PoseTrajectoryReplan &  msg)

Definition at line 140 of file R2RosTrajectoryManager.cpp.

void R2RosTrajectoryManager::poseSettingsCallback ( const r2_msgs::ControllerPoseSettings &  msg)

Definition at line 122 of file R2RosTrajectoryManager.cpp.

void R2RosTrajectoryManager::poseStatesCallback ( const r2_msgs::PoseState &  msg)

Definition at line 128 of file R2RosTrajectoryManager.cpp.

void R2RosTrajectoryManager::setCartesianParameters ( std::vector< double >  priorityNum,
std::vector< double >  linearTol,
std::vector< double >  angularTol,
double  momLimit,
double  taskGain,
int  ikMaxItr,
double  ikMaxTwist 
)

Definition at line 38 of file R2RosTrajectoryManager.cpp.

Definition at line 176 of file R2RosTrajectoryManager.cpp.

void R2RosTrajectoryManager::writeJointControl ( const r2_msgs::JointControlDataArray &  jointControl_out) [protected, virtual]

Definition at line 172 of file R2RosTrajectoryManager.cpp.

void R2RosTrajectoryManager::writeJointState ( const sensor_msgs::JointState &  jointState_out) [protected, virtual]

Definition at line 164 of file R2RosTrajectoryManager.cpp.

void R2RosTrajectoryManager::writeStatus ( const actionlib_msgs::GoalStatusArray &  goalStatusMsg_out) [protected, virtual]

Definition at line 158 of file R2RosTrajectoryManager.cpp.


Member Data Documentation

Definition at line 66 of file R2RosTrajectoryManager.hpp.

Definition at line 55 of file R2RosTrajectoryManager.hpp.

Definition at line 67 of file R2RosTrajectoryManager.hpp.

Definition at line 62 of file R2RosTrajectoryManager.hpp.

publishers and subscribers

Definition at line 52 of file R2RosTrajectoryManager.hpp.

sensor_msgs::JointState R2RosTrajectoryManager::jointCommandOutMsg [private]

Definition at line 82 of file R2RosTrajectoryManager.hpp.

Definition at line 60 of file R2RosTrajectoryManager.hpp.

r2_msgs::JointCommand R2RosTrajectoryManager::jointCommandsMsg [private]

Definition at line 78 of file R2RosTrajectoryManager.hpp.

Definition at line 63 of file R2RosTrajectoryManager.hpp.

r2_msgs::JointTrajectoryReplan R2RosTrajectoryManager::jointRefsMsg [private]

Definition at line 75 of file R2RosTrajectoryManager.hpp.

Definition at line 59 of file R2RosTrajectoryManager.hpp.

r2_msgs::ControllerJointSettings R2RosTrajectoryManager::jointSettingsMsg [private]

messages

Definition at line 74 of file R2RosTrajectoryManager.hpp.

Definition at line 57 of file R2RosTrajectoryManager.hpp.

Definition at line 61 of file R2RosTrajectoryManager.hpp.

sensor_msgs::JointState R2RosTrajectoryManager::jointStatesMsg [private]

Definition at line 77 of file R2RosTrajectoryManager.hpp.

r2_msgs::JointControlDataArray R2RosTrajectoryManager::jointStatusMsg [private]

Definition at line 80 of file R2RosTrajectoryManager.hpp.

Definition at line 64 of file R2RosTrajectoryManager.hpp.

Definition at line 50 of file R2RosTrajectoryManager.hpp.

Definition at line 53 of file R2RosTrajectoryManager.hpp.

r2_msgs::PoseState R2RosTrajectoryManager::poseCommandOutMsg [private]

Definition at line 88 of file R2RosTrajectoryManager.hpp.

Definition at line 70 of file R2RosTrajectoryManager.hpp.

r2_msgs::PoseState R2RosTrajectoryManager::poseCommandsMsg [private]

Definition at line 84 of file R2RosTrajectoryManager.hpp.

Definition at line 71 of file R2RosTrajectoryManager.hpp.

r2_msgs::PoseTrajectoryReplan R2RosTrajectoryManager::poseRefsMsg [private]

Definition at line 85 of file R2RosTrajectoryManager.hpp.

Definition at line 56 of file R2RosTrajectoryManager.hpp.

std::queue<r2_msgs::PoseTrajectoryReplan> R2RosTrajectoryManager::poseRefsQueue [private]

Definition at line 86 of file R2RosTrajectoryManager.hpp.

Definition at line 68 of file R2RosTrajectoryManager.hpp.

Definition at line 69 of file R2RosTrajectoryManager.hpp.

Definition at line 54 of file R2RosTrajectoryManager.hpp.

r2_msgs::PoseState R2RosTrajectoryManager::poseStatesOutMsg [private]

Definition at line 87 of file R2RosTrajectoryManager.hpp.

r2_msgs::JointCommand R2RosTrajectoryManager::prevJointCommandsMsg [private]

Definition at line 79 of file R2RosTrajectoryManager.hpp.

sensor_msgs::JointState R2RosTrajectoryManager::prevJointStatesMsg [private]

Definition at line 76 of file R2RosTrajectoryManager.hpp.

Definition at line 96 of file R2RosTrajectoryManager.hpp.

Definition at line 95 of file R2RosTrajectoryManager.hpp.

r2_msgs::ControllerJointSettings R2RosTrajectoryManager::replanJointSettings [private]

Definition at line 94 of file R2RosTrajectoryManager.hpp.

Definition at line 99 of file R2RosTrajectoryManager.hpp.

Definition at line 98 of file R2RosTrajectoryManager.hpp.

Definition at line 97 of file R2RosTrajectoryManager.hpp.

Definition at line 91 of file R2RosTrajectoryManager.hpp.

trajectory_msgs::JointTrajectory R2RosTrajectoryManager::trajInMsg [private]

Definition at line 81 of file R2RosTrajectoryManager.hpp.

RosMsgTreeFk R2RosTrajectoryManager::treeFk [private]

Definition at line 101 of file R2RosTrajectoryManager.hpp.

std::string R2RosTrajectoryManager::urdfFile [private]

Definition at line 90 of file R2RosTrajectoryManager.hpp.

Definition at line 92 of file R2RosTrajectoryManager.hpp.


The documentation for this class was generated from the following files:


robodyn_ros
Author(s):
autogenerated on Thu Jun 6 2019 18:14:40