Classes | Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
robot_calibration::ChainManager Class Reference

Manages moving joints to a new pose, determining when they are settled, and returning current joint_states. More...

#include <chain_manager.h>

Classes

struct  ChainController
 

Public Member Functions

 ChainManager (ros::NodeHandle &nh, double wait_time=15.0)
 Constructor, sets up chains from ros parameters. More...
 
std::vector< std::string > getChainJointNames (const std::string &chain_name)
 Get the joint names associated with a chain. Mainly for testing. More...
 
std::vector< std::string > getChains ()
 Get the names of chains. Mainly for testing. More...
 
std::string getPlanningGroupName (const std::string &chain_name)
 
bool getState (sensor_msgs::JointState *state)
 Get the current JointState message. More...
 
bool moveToState (const sensor_msgs::JointState &state)
 Send commands to all managed joints. The ChainManager automatically figures out which controller to send these to. More...
 
bool waitToSettle ()
 Wait for joints to settle. More...
 

Private Types

typedef actionlib::SimpleActionClient< moveit_msgs::MoveGroupAction > MoveGroupClient
 
typedef boost::shared_ptr< MoveGroupClientMoveGroupClientPtr
 
typedef boost::shared_ptr< const moveit_msgs::MoveGroupResult > MoveGroupResultPtr
 
typedef actionlib::SimpleActionClient< control_msgs::FollowJointTrajectoryAction > TrajectoryClient
 

Private Member Functions

trajectory_msgs::JointTrajectoryPoint makePoint (const sensor_msgs::JointState &state, const std::vector< std::string > &joints)
 
void stateCallback (const sensor_msgs::JointStateConstPtr &msg)
 

Private Attributes

std::vector< boost::shared_ptr< ChainController > > controllers_
 
double duration_
 
MoveGroupClientPtr move_group_
 
sensor_msgs::JointState state_
 
bool state_is_valid_
 
boost::mutex state_mutex_
 
ros::Subscriber subscriber_
 
double velocity_factor_
 

Detailed Description

Manages moving joints to a new pose, determining when they are settled, and returning current joint_states.

Definition at line 37 of file chain_manager.h.

Member Typedef Documentation

Definition at line 40 of file chain_manager.h.

Definition at line 41 of file chain_manager.h.

typedef boost::shared_ptr<const moveit_msgs::MoveGroupResult> robot_calibration::ChainManager::MoveGroupResultPtr
private

Definition at line 42 of file chain_manager.h.

typedef actionlib::SimpleActionClient<control_msgs::FollowJointTrajectoryAction> robot_calibration::ChainManager::TrajectoryClient
private

Definition at line 39 of file chain_manager.h.

Constructor & Destructor Documentation

robot_calibration::ChainManager::ChainManager ( ros::NodeHandle nh,
double  wait_time = 15.0 
)

Constructor, sets up chains from ros parameters.

Parameters
nhThe node handle, sets namespace for parameters.
wait_timeThe time to wait for each action to come up.

Definition at line 25 of file chain_manager.cpp.

Member Function Documentation

std::vector< std::string > robot_calibration::ChainManager::getChainJointNames ( const std::string &  chain_name)

Get the joint names associated with a chain. Mainly for testing.

Definition at line 301 of file chain_manager.cpp.

std::vector< std::string > robot_calibration::ChainManager::getChains ( )

Get the names of chains. Mainly for testing.

Definition at line 291 of file chain_manager.cpp.

std::string robot_calibration::ChainManager::getPlanningGroupName ( const std::string &  chain_name)

Definition at line 313 of file chain_manager.cpp.

bool robot_calibration::ChainManager::getState ( sensor_msgs::JointState *  state)

Get the current JointState message.

Definition at line 124 of file chain_manager.cpp.

trajectory_msgs::JointTrajectoryPoint robot_calibration::ChainManager::makePoint ( const sensor_msgs::JointState &  state,
const std::vector< std::string > &  joints 
)
private

Definition at line 132 of file chain_manager.cpp.

bool robot_calibration::ChainManager::moveToState ( const sensor_msgs::JointState &  state)

Send commands to all managed joints. The ChainManager automatically figures out which controller to send these to.

Returns
False if failed.

Definition at line 156 of file chain_manager.cpp.

void robot_calibration::ChainManager::stateCallback ( const sensor_msgs::JointStateConstPtr &  msg)
private

Definition at line 85 of file chain_manager.cpp.

bool robot_calibration::ChainManager::waitToSettle ( )

Wait for joints to settle.

Definition at line 233 of file chain_manager.cpp.

Member Data Documentation

std::vector<boost::shared_ptr<ChainController> > robot_calibration::ChainManager::controllers_
private

Definition at line 119 of file chain_manager.h.

double robot_calibration::ChainManager::duration_
private

Definition at line 118 of file chain_manager.h.

MoveGroupClientPtr robot_calibration::ChainManager::move_group_
private

Definition at line 120 of file chain_manager.h.

sensor_msgs::JointState robot_calibration::ChainManager::state_
private

Definition at line 114 of file chain_manager.h.

bool robot_calibration::ChainManager::state_is_valid_
private

Definition at line 115 of file chain_manager.h.

boost::mutex robot_calibration::ChainManager::state_mutex_
private

Definition at line 113 of file chain_manager.h.

ros::Subscriber robot_calibration::ChainManager::subscriber_
private

Definition at line 112 of file chain_manager.h.

double robot_calibration::ChainManager::velocity_factor_
private

Definition at line 121 of file chain_manager.h.


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


robot_calibration
Author(s): Michael Ferguson
autogenerated on Tue Nov 3 2020 17:30:30