Classes | Namespaces | Functions
RosMsgConverter.h File Reference

Provides helper functions for converting to and from ros messages. More...

#include <trajectory_msgs/JointTrajectory.h>
#include "r2_msgs/PoseTrajectory.h"
#include <sensor_msgs/JointState.h>
#include "r2_msgs/PoseState.h"
#include "r2_msgs/JointControlDataArray.h"
#include "r2_msgs/WrenchState.h"
#include "r2_msgs/JointCommand.h"
#include "r2_msgs/ToolFrame.h"
#include <kdl/jntarrayvel.hpp>
#include <kdl/frameacc.hpp>
#include <kdl/segment.hpp>
#include <kdl/jntarrayacc.hpp>
Include dependency graph for RosMsgConverter.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  RosMsgConverter::JointAcc
struct  RosMsgConverter::JointCommand
struct  RosMsgConverter::JointVel
struct  RosMsgConverter::ToolFrame

Namespaces

namespace  RosMsgConverter

Functions

void RosMsgConverter::JointCommandToJointCommandMap (const r2_msgs::JointCommand &jointCommand, std::map< std::string, JointCommand > &jointCommandMap)
void RosMsgConverter::JointControlDataToCoeffStateMap (const r2_msgs::JointControlDataArray &jointData, std::map< std::string, r2_msgs::JointControlCoeffState > &jointMap)
void RosMsgConverter::JointStateToJntArray (const sensor_msgs::JointState &jointState, const std::vector< std::string > jointNames, KDL::JntArray &jointArray)
 JointStateToJntArray.
void RosMsgConverter::JointStateToJntArrayAcc (const sensor_msgs::JointState &jointState, const std::vector< std::string > jointNames, KDL::JntArrayAcc &jointArray)
 Acc term contains effort ///.
void RosMsgConverter::JointStateToJntArrayVel (const sensor_msgs::JointState &jointState, const std::vector< std::string > jointNames, KDL::JntArrayVel &jointArray)
 JointStateToJntArrayVel.
void RosMsgConverter::JointStateToJntMap (const sensor_msgs::JointState &jointState, std::map< std::string, double > &jointMap)
 JointStateToJntMap creates a map of jointName and position.
void RosMsgConverter::JointStateToJointAccMap (const sensor_msgs::JointState &jointState, std::map< std::string, JointAcc > &jointMap)
 JointStateEffortToJntMap ToJntMap creates a map of jointName and effort.
void RosMsgConverter::JointStateToJointVelMap (const sensor_msgs::JointState &jointState, std::map< std::string, JointVel > &jointMap)
 JointStateVel ToJntMap creates a map of jointName and velocity.
void RosMsgConverter::PoseStateToFrame (const r2_msgs::PoseState &poseState, const std::string &baseName, const std::string &tipName, KDL::Frame &frame)
 PoseStateToFrame.
void RosMsgConverter::PoseStateToFrameAcc (const r2_msgs::PoseState &poseState, const std::string &baseName, const std::string &tipName, KDL::FrameAcc &frame)
 PoseStateToFrameAcc.
void RosMsgConverter::PoseStateToFrameAccMap (const r2_msgs::PoseState &poseState, const std::string &base, std::map< std::string, KDL::FrameAcc > &frameaccs)
 updates a map of all the frames in poseState with their new location and orientations
void RosMsgConverter::PoseStateToFrameMap (const r2_msgs::PoseState &poseState, const std::string &base, std::map< std::string, KDL::Frame > &frames)
 updates a map of all the frames in poseState with their new location and orientations
void RosMsgConverter::PoseStateToFrameVel (const r2_msgs::PoseState &poseState, const std::string &baseName, const std::string &tipName, KDL::FrameVel &frame)
 PoseStateToFrameVel.
void RosMsgConverter::PoseStateToFrameVelMap (const r2_msgs::PoseState &poseState, const std::string &base, std::map< std::string, KDL::FrameVel > &framevels)
 updates a map of all the frames in poseState with their new location and orientations
void RosMsgConverter::ToolFrameToSegment (const r2_msgs::ToolFrame &toolFrame, std::vector< ToolFrame > &segmentList)
 creates a segment map from a toolFrame message
void RosMsgConverter::ToolFrameToSegmentAdd (const r2_msgs::ToolFrame &toolFrame, std::vector< ToolFrame > &segmentList, std::vector< ToolFrame > &addSegmentList)
void RosMsgConverter::ToolFrameToSegmentRemove (const r2_msgs::ToolFrame &toolFrame, std::vector< ToolFrame > &removeSegmentList)
KDL::Wrench RosMsgConverter::wrenchMsgToWrench (const geometry_msgs::Wrench &wrenchMsg)
void RosMsgConverter::WrenchStateToWrenchMap (const r2_msgs::WrenchState &wrenchState, std::map< std::string, KDL::Wrench > &wrenchMap)
geometry_msgs::Wrench RosMsgConverter::wrenchToWrenchMsg (const KDL::Wrench &wrench)

Detailed Description

Provides helper functions for converting to and from ros messages.

Author:
Ross Taylor
Date:
Aug 31, 2012
Author:
Allison Thackston
Date:
July 13, 2013

Definition in file RosMsgConverter.h.



robodyn_utilities
Author(s):
autogenerated on Thu Jun 6 2019 18:56:08