chain_manager.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2014-2015 Fetch Robotics Inc.
3  * Copyright (C) 2013-2014 Unbounded Robotics Inc.
4  *
5  * Licensed under the Apache License, Version 2.0 (the "License");
6  * you may not use this file except in compliance with the License.
7  * You may obtain a copy of the License at
8  *
9  * http://www.apache.org/licenses/LICENSE-2.0
10  *
11  * Unless required by applicable law or agreed to in writing, software
12  * distributed under the License is distributed on an "AS IS" BASIS,
13  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14  * See the License for the specific language governing permissions and
15  * limitations under the License.
16  */
17 
18 // Author: Michael Ferguson
19 
20 #ifndef ROBOT_CALIBRATION_CAPTURE_CHAIN_MANAGER_H
21 #define ROBOT_CALIBRATION_CAPTURE_CHAIN_MANAGER_H
22 
23 #include <ros/ros.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>
29 
30 namespace robot_calibration
31 {
32 
38 {
43 
44  // This controls a single chain
46  {
47  ChainController(const std::string& name,
48  const std::string& topic,
49  const std::string& planning_group) :
50  client(topic, true),
51  chain_name(name),
52  chain_planning_group(planning_group)
53  {
54  }
55 
56  bool shouldPlan()
57  {
58  return (chain_planning_group != "");
59  }
60 
61  TrajectoryClient client;
62  std::string chain_name;
63  std::string chain_planning_group;
64  std::vector<std::string> joint_names;
65  };
66 
67 public:
73  ChainManager(ros::NodeHandle& nh, double wait_time = 15.0);
74 
80  bool moveToState(const sensor_msgs::JointState& state);
81 
85  bool waitToSettle();
86 
90  bool getState(sensor_msgs::JointState* state);
91 
95  std::vector<std::string> getChains();
96 
100  std::vector<std::string> getChainJointNames(const std::string& chain_name);
101 
102  // Mainly for testing
103  std::string getPlanningGroupName(const std::string& chain_name);
104 
105 private:
106  void stateCallback(const sensor_msgs::JointStateConstPtr& msg);
107 
108  trajectory_msgs::JointTrajectoryPoint makePoint(const sensor_msgs::JointState& state,
109  const std::vector<std::string>& joints);
110 
111  // Subscriber for joint_states topic, storage of message
113  boost::mutex state_mutex_;
114  sensor_msgs::JointState state_;
116 
117  // Mechanisms for passing commands to controllers
118  double duration_;
119  std::vector<boost::shared_ptr<ChainController> > controllers_;
120  MoveGroupClientPtr move_group_;
121  double velocity_factor_; // scaling factor to slow down move_group plans
122 };
123 
124 } // namespace robot_calibration
125 
126 #endif // ROBOT_CALIBRATION_CAPTURE_CHAIN_MANAGER_H
std::string getPlanningGroupName(const std::string &chain_name)
actionlib::SimpleActionClient< moveit_msgs::MoveGroupAction > MoveGroupClient
Definition: chain_manager.h:40
Manages moving joints to a new pose, determining when they are settled, and returning current joint_s...
Definition: chain_manager.h:37
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.
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
Definition: chain_manager.h:41
boost::shared_ptr< const moveit_msgs::MoveGroupResult > MoveGroupResultPtr
Definition: chain_manager.h:42
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)
Definition: chain_manager.h:47
MoveGroupClientPtr move_group_
std::vector< boost::shared_ptr< ChainController > > controllers_
actionlib::SimpleActionClient< control_msgs::FollowJointTrajectoryAction > TrajectoryClient
Definition: chain_manager.h:39
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.


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