20 #ifndef ROBOT_CALIBRATION_CAPTURE_CHAIN_MANAGER_H 21 #define ROBOT_CALIBRATION_CAPTURE_CHAIN_MANAGER_H 24 #include <boost/thread/mutex.hpp> 25 #include <sensor_msgs/JointState.h> 27 #include <control_msgs/FollowJointTrajectoryAction.h> 28 #include <moveit_msgs/MoveGroupAction.h> 48 const std::string& topic,
49 const std::string& planning_group) :
80 bool moveToState(
const sensor_msgs::JointState& state);
90 bool getState(sensor_msgs::JointState* state);
106 void stateCallback(
const sensor_msgs::JointStateConstPtr& msg);
108 trajectory_msgs::JointTrajectoryPoint
makePoint(
const sensor_msgs::JointState& state,
109 const std::vector<std::string>& joints);
126 #endif // ROBOT_CALIBRATION_CAPTURE_CHAIN_MANAGER_H
std::string getPlanningGroupName(const std::string &chain_name)
actionlib::SimpleActionClient< moveit_msgs::MoveGroupAction > MoveGroupClient
std::string chain_planning_group
Manages moving joints to a new pose, determining when they are settled, and returning current joint_s...
void stateCallback(const sensor_msgs::JointStateConstPtr &msg)
std::vector< std::string > getChainJointNames(const std::string &chain_name)
Get the joint names associated with a chain. Mainly for testing.
sensor_msgs::JointState state_
bool waitToSettle()
Wait for joints to settle.
boost::mutex state_mutex_
trajectory_msgs::JointTrajectoryPoint makePoint(const sensor_msgs::JointState &state, const std::vector< std::string > &joints)
Calibration code lives under this namespace.
boost::shared_ptr< MoveGroupClient > MoveGroupClientPtr
std::vector< std::string > joint_names
boost::shared_ptr< const moveit_msgs::MoveGroupResult > MoveGroupResultPtr
bool moveToState(const sensor_msgs::JointState &state)
Send commands to all managed joints. The ChainManager automatically figures out which controller to s...
bool getState(sensor_msgs::JointState *state)
Get the current JointState message.
ChainController(const std::string &name, const std::string &topic, const std::string &planning_group)
MoveGroupClientPtr move_group_
std::vector< boost::shared_ptr< ChainController > > controllers_
ros::Subscriber subscriber_
actionlib::SimpleActionClient< control_msgs::FollowJointTrajectoryAction > TrajectoryClient
std::vector< std::string > getChains()
Get the names of chains. Mainly for testing.
ChainManager(ros::NodeHandle &nh, double wait_time=15.0)
Constructor, sets up chains from ros parameters.