chain_manager.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2014-2016 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 
21 
22 namespace robot_calibration
23 {
24 
26  state_is_valid_(false)
27 {
28  // We cannot do much without some kinematic chains
29  if (!nh.hasParam("chains"))
30  {
31  ROS_WARN("No chains defined.");
32  return;
33  }
34 
35  // Get chains
36  XmlRpc::XmlRpcValue chains;
37  nh.getParam("chains", chains);
39 
40  // Construct each chain to manage
41  for (int i = 0; i < chains.size(); ++i)
42  {
43  std::string name, topic, group;
44  name = static_cast<std::string>(chains[i]["name"]);
45  group = static_cast<std::string>(chains[i]["planning_group"]);
46 
47  if (chains[i].hasMember("topic"))
48  {
49  topic = static_cast<std::string>(chains[i]["topic"]);
50 
51  boost::shared_ptr<ChainController> controller(new ChainController(name, topic, group));
52 
53  for (int j = 0; j < chains[i]["joints"].size(); ++j)
54  {
55  controller->joint_names.push_back(static_cast<std::string>(chains[i]["joints"][j]));
56  }
57 
58  ROS_INFO("Waiting for %s...", topic.c_str());
59  if (!controller->client.waitForServer(ros::Duration(wait_time)))
60  {
61  ROS_WARN("Failed to connect to %s", topic.c_str());
62  }
63 
64  if (controller->shouldPlan() && (!move_group_))
65  {
66  move_group_.reset(new MoveGroupClient("move_group", true));
67  if (!move_group_->waitForServer(ros::Duration(wait_time)))
68  {
69  ROS_WARN("Failed to connect to move_group");
70  }
71  }
72 
73  controllers_.push_back(controller);
74  }
75  }
76 
77  // Parameter to set movement time
78  nh.param<double>("duration", duration_, 5.0);
79 
80  // Parameter to set velocity scaling factor for move_group
81  nh.param<double>("velocity_factor", velocity_factor_, 1.0);
82 
83  subscriber_ = nh.subscribe("/joint_states", 10, &ChainManager::stateCallback, this);
84 }
85 
86 void ChainManager::stateCallback(const sensor_msgs::JointStateConstPtr& msg)
87 {
88  if (msg->name.size() != msg->position.size())
89  {
90  ROS_ERROR("JointState Error: name array is not same size as position array.");
91  return;
92  }
93 
94  if (msg->position.size() != msg->velocity.size())
95  {
96  ROS_ERROR("JointState Error: position array is not same size as velocity array.");
97  return;
98  }
99 
100  boost::mutex::scoped_lock lock(state_mutex_);
101  // Update each joint based on message
102  for (size_t msg_j = 0; msg_j < msg->name.size(); msg_j++)
103  {
104  size_t state_j;
105  for (state_j = 0; state_j < state_.name.size(); state_j++)
106  {
107  if (state_.name[state_j] == msg->name[msg_j])
108  {
109  state_.position[state_j] = msg->position[msg_j];
110  state_.velocity[state_j] = msg->velocity[msg_j];
111  break;
112  }
113  }
114  if (state_j == state_.name.size())
115  {
116  // New joint
117  state_.name.push_back(msg->name[msg_j]);
118  state_.position.push_back(msg->position[msg_j]);
119  state_.velocity.push_back(msg->velocity[msg_j]);
120  }
121  }
122  state_is_valid_ = true;
123 }
124 
125 bool ChainManager::getState(sensor_msgs::JointState* state)
126 {
127  boost::mutex::scoped_lock lock(state_mutex_);
128  *state = state_;
129  return state_is_valid_;
130 }
131 
132 trajectory_msgs::JointTrajectoryPoint
133 ChainManager::makePoint(const sensor_msgs::JointState& state, const std::vector<std::string>& joints)
134 {
135  trajectory_msgs::JointTrajectoryPoint p;
136  for (size_t i = 0; i < joints.size(); ++i)
137  {
138  for (size_t j = 0; j < state.name.size(); ++j)
139  {
140  if (joints[i] == state.name[j])
141  {
142  p.positions.push_back(state.position[j]);
143  break;
144  }
145  }
146  p.velocities.push_back(0.0);
147  p.accelerations.push_back(0.0);
148  if (p.velocities.size() != p.positions.size())
149  {
150  ROS_ERROR_STREAM("Bad move to state, missing " << joints[i]);
151  exit(-1);
152  }
153  }
154  return p;
155 }
156 
157 bool ChainManager::moveToState(const sensor_msgs::JointState& state)
158 {
159  double max_duration = duration_;
160 
161  // Split into different controllers
162  for (size_t i = 0; i < controllers_.size(); ++i)
163  {
164  control_msgs::FollowJointTrajectoryGoal goal;
165  goal.trajectory.joint_names = controllers_[i]->joint_names;
166 
167  trajectory_msgs::JointTrajectoryPoint p = makePoint(state, controllers_[i]->joint_names);
168  if (controllers_[i]->shouldPlan())
169  {
170  // Call MoveIt
171  moveit_msgs::MoveGroupGoal moveit_goal;
172  moveit_goal.request.group_name = controllers_[i]->chain_planning_group;
173  moveit_goal.request.num_planning_attempts = 1;
174  moveit_goal.request.allowed_planning_time = 5.0;
175 
176  moveit_msgs::Constraints c1;
177  c1.joint_constraints.resize(controllers_[i]->joint_names.size());
178  for (size_t c = 0; c < controllers_[i]->joint_names.size(); c++)
179  {
180  c1.joint_constraints[c].joint_name = controllers_[i]->joint_names[c];
181  c1.joint_constraints[c].position = p.positions[c];
182  c1.joint_constraints[c].tolerance_above = 0.01;
183  c1.joint_constraints[c].tolerance_below = 0.01;
184  c1.joint_constraints[c].weight = 1.0;
185  }
186  moveit_goal.request.goal_constraints.push_back(c1);
187 
188  // Reduce speed
189  moveit_goal.request.max_velocity_scaling_factor = velocity_factor_;
190 
191  // All diffs
192  moveit_goal.request.start_state.is_diff = true;
193  moveit_goal.planning_options.planning_scene_diff.is_diff = true;
194  moveit_goal.planning_options.planning_scene_diff.robot_state.is_diff = true;
195 
196  // Just make the plan, we will execute it
197  moveit_goal.planning_options.plan_only = true;
198 
199  move_group_->sendGoal(moveit_goal);
200  move_group_->waitForResult();
201  MoveGroupResultPtr result = move_group_->getResult();
202  if (result->error_code.val != moveit_msgs::MoveItErrorCodes::SUCCESS)
203  {
204  // Unable to plan, return error
205  return false;
206  }
207 
208  goal.trajectory = result->planned_trajectory.joint_trajectory;
209  max_duration = std::max(max_duration, goal.trajectory.points[goal.trajectory.points.size()-1].time_from_start.toSec());
210  }
211  else
212  {
213  // Go directly to point
214  p.time_from_start = ros::Duration(duration_);
215  goal.trajectory.points.push_back(p);
216  }
217 
218  goal.goal_time_tolerance = ros::Duration(1.0);
219 
220  // Call actions
221  controllers_[i]->client.sendGoal(goal);
222  }
223 
224  // Wait for results
225  for (size_t i = 0; i < controllers_.size(); ++i)
226  {
227  controllers_[i]->client.waitForResult(ros::Duration(max_duration*1.5));
228  // TODO: catch errors with clients
229  }
230 
231  return true;
232 }
233 
235 {
236  sensor_msgs::JointState state;
237 
238  if (controllers_.empty())
239  {
240  // Nothing to wait for
241  return true;
242  }
243 
244  // Reset to invalid so we know state is not stale
245  {
246  boost::mutex::scoped_lock lock(state_mutex_);
247  state_is_valid_ = false;
248  }
249 
250  // TODO: timeout?
251  while (true)
252  {
253  bool settled = true;
254 
255  if (getState(&state))
256  {
257 
258  // For each joint in state message
259  for (size_t j = 0; j < state.name.size(); ++j)
260  {
261  // Is this joint even a concern?
262  if (fabs(state.velocity[j]) < 0.001)
263  continue;
264 
265  for (size_t i = 0; i < controllers_.size(); ++i)
266  {
267  for (size_t k = 0; k < controllers_[i]->joint_names.size(); ++k)
268  {
269  if (controllers_[i]->joint_names[k] == state.name[j])
270  {
271  settled = false;
272  break;
273  }
274  }
275  }
276 
277  // If at least one joint is not settled, break out of this for loop
278  if (!settled)
279  break;
280  }
281  }
282  else
283  {
284  // State is not yet valid, can't determine if settled
285  settled = false;
286  }
287 
288  // If all joints are settled, break out of while loop
289  if (settled)
290  break;
291 
292  ros::spinOnce();
293  }
294 
295  return true;
296 }
297 
298 std::vector<std::string> ChainManager::getChains()
299 {
300  std::vector<std::string> chains;
301  for (size_t i = 0; i < controllers_.size(); ++i)
302  {
303  chains.push_back(controllers_[i]->chain_name);
304  }
305  return chains;
306 }
307 
308 std::vector<std::string> ChainManager::getChainJointNames(
309  const std::string& chain_name)
310 {
311  for (size_t i = 0; i < controllers_.size(); ++i)
312  {
313  if (controllers_[i]->chain_name == chain_name)
314  return controllers_[i]->joint_names;
315  }
316  std::vector<std::string> empty;
317  return empty;
318 }
319 
321  const std::string& chain_name)
322 {
323  for (size_t i = 0; i < controllers_.size(); ++i)
324  {
325  if (controllers_[i]->chain_name == chain_name)
326  return controllers_[i]->chain_planning_group;
327  }
328  std::vector<std::string> empty;
329  return std::string("");
330 }
331 
332 } // namespace robot_calibration
XmlRpc::XmlRpcValue::size
int size() const
robot_calibration::ChainManager::moveToState
bool moveToState(const sensor_msgs::JointState &state)
Send commands to all managed joints. The ChainManager automatically figures out which controller to s...
Definition: chain_manager.cpp:157
chain_manager.h
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
boost::shared_ptr
robot_calibration::ChainManager::ChainManager
ChainManager(ros::NodeHandle &nh, double wait_time=15.0)
Constructor, sets up chains from ros parameters.
Definition: chain_manager.cpp:25
robot_calibration::ChainManager::velocity_factor_
double velocity_factor_
Definition: chain_manager.h:121
robot_calibration::ChainManager::getState
bool getState(sensor_msgs::JointState *state)
Get the current JointState message.
Definition: chain_manager.cpp:125
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
robot_calibration::ChainManager::duration_
double duration_
Definition: chain_manager.h:118
ros::spinOnce
ROSCPP_DECL void spinOnce()
robot_calibration::ChainManager::subscriber_
ros::Subscriber subscriber_
Definition: chain_manager.h:112
robot_calibration::ChainManager::state_is_valid_
bool state_is_valid_
Definition: chain_manager.h:115
robot_calibration::ChainManager::waitToSettle
bool waitToSettle()
Wait for joints to settle.
Definition: chain_manager.cpp:234
robot_calibration::ChainManager::getChainJointNames
std::vector< std::string > getChainJointNames(const std::string &chain_name)
Get the joint names associated with a chain. Mainly for testing.
Definition: chain_manager.cpp:308
robot_calibration::ChainManager::stateCallback
void stateCallback(const sensor_msgs::JointStateConstPtr &msg)
Definition: chain_manager.cpp:86
name
std::string name
robot_calibration::ChainManager::getPlanningGroupName
std::string getPlanningGroupName(const std::string &chain_name)
Definition: chain_manager.cpp:320
ROS_ERROR
#define ROS_ERROR(...)
robot_calibration::ChainManager::MoveGroupClient
actionlib::SimpleActionClient< moveit_msgs::MoveGroupAction > MoveGroupClient
Definition: chain_manager.h:40
ros::NodeHandle::hasParam
bool hasParam(const std::string &key) const
ROS_WARN
#define ROS_WARN(...)
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
robot_calibration::ChainManager::state_mutex_
boost::mutex state_mutex_
Definition: chain_manager.h:113
robot_calibration::ChainManager::makePoint
trajectory_msgs::JointTrajectoryPoint makePoint(const sensor_msgs::JointState &state, const std::vector< std::string > &joints)
Definition: chain_manager.cpp:133
XmlRpc::XmlRpcValue::getType
const Type & getType() const
XmlRpc::XmlRpcValue::TypeArray
TypeArray
robot_calibration
Calibration code lives under this namespace.
Definition: base_calibration.h:28
robot_calibration::ChainManager::controllers_
std::vector< boost::shared_ptr< ChainController > > controllers_
Definition: chain_manager.h:119
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
ROS_INFO
#define ROS_INFO(...)
ROS_ASSERT
#define ROS_ASSERT(cond)
ros::Duration
robot_calibration::ChainManager::state_
sensor_msgs::JointState state_
Definition: chain_manager.h:114
robot_calibration::ChainManager::getChains
std::vector< std::string > getChains()
Get the names of chains. Mainly for testing.
Definition: chain_manager.cpp:298
XmlRpc::XmlRpcValue
ros::NodeHandle
robot_calibration::ChainManager::ChainController
Definition: chain_manager.h:45
robot_calibration::ChainManager::move_group_
MoveGroupClientPtr move_group_
Definition: chain_manager.h:120


robot_calibration
Author(s): Michael Ferguson
autogenerated on Fri Sep 1 2023 02:52:01