capture_manager.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2018-2022 Michael Ferguson
3  * Copyright (C) 2015 Fetch Robotics Inc.
4  * Copyright (C) 2013-2014 Unbounded Robotics Inc.
5  *
6  * Licensed under the Apache License, Version 2.0 (the "License");
7  * you may not use this file except in compliance with the License.
8  * You may obtain a copy of the License at
9  *
10  * http://www.apache.org/licenses/LICENSE-2.0
11  *
12  * Unless required by applicable law or agreed to in writing, software
13  * distributed under the License is distributed on an "AS IS" BASIS,
14  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
15  * See the License for the specific language governing permissions and
16  * limitations under the License.
17  */
18 
19 // Author: Michael Ferguson
20 
21 #include <ros/ros.h>
22 #include <std_msgs/String.h>
24 
25 namespace robot_calibration
26 {
27 
29 {
30 }
31 
33 {
34  data_pub_ = nh.advertise<robot_calibration_msgs::CalibrationData>("/calibration_data", 10);
35  urdf_pub_ = nh.advertise<std_msgs::String>("/robot_description", 1, true /* latched */);
36 
37  // Create chain manager
38  chain_manager_ = new ChainManager(nh);
39 
40  // Load feature finders
42  {
43  ROS_FATAL("Unable to load feature finders!");
44  return false;
45  }
46 
47  // Get the robot_description and republish it
48  if (!nh.getParam("/robot_description", description_msg_.data))
49  {
50  ROS_FATAL("robot_description not set!");
51  return false;
52  }
54 
55  return true;
56 }
57 
58 bool CaptureManager::moveToState(const sensor_msgs::JointState& state)
59 {
60  if (!chain_manager_->moveToState(state))
61  {
62  return false;
63  }
64 
65  // Wait for things to settle
67  return true;
68 }
69 
70 bool CaptureManager::captureFeatures(const std::vector<std::string>& feature_names,
71  robot_calibration_msgs::CalibrationData& msg)
72 {
73  for (auto it = finders_.begin(); it != finders_.end(); ++it)
74  {
75  if (feature_names.empty() ||
76  std::find(feature_names.begin(), feature_names.end(), it->first) != feature_names.end())
77  {
78  if (!it->second->find(&msg))
79  {
80  ROS_WARN("%s failed to capture features.", it->first.c_str());
81  return false;
82  }
83  }
84  }
85  chain_manager_->getState(&msg.joint_states);
86  // Publish calibration data message.
87  data_pub_.publish(msg);
88  return true;
89 }
90 
92 {
93  return description_msg_.data;
94 }
95 
96 } // namespace robot_calibration
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
robot_calibration::CaptureManager::CaptureManager
CaptureManager()
Definition: capture_manager.cpp:28
robot_calibration::CaptureManager::getUrdf
std::string getUrdf()
Definition: capture_manager.cpp:91
robot_calibration::ChainManager::getState
bool getState(sensor_msgs::JointState *state)
Get the current JointState message.
Definition: chain_manager.cpp:125
capture_manager.h
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros.h
robot_calibration::CaptureManager::init
bool init(ros::NodeHandle &nh)
Definition: capture_manager.cpp:32
robot_calibration::CaptureManager::captureFeatures
bool captureFeatures(const std::vector< std::string > &feature_names, robot_calibration_msgs::CalibrationData &msg)
Definition: capture_manager.cpp:70
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
robot_calibration::ChainManager::waitToSettle
bool waitToSettle()
Wait for joints to settle.
Definition: chain_manager.cpp:234
robot_calibration::CaptureManager::data_pub_
ros::Publisher data_pub_
Definition: capture_manager.h:42
robot_calibration::CaptureManager::finders_
robot_calibration::FeatureFinderMap finders_
Definition: capture_manager.h:48
robot_calibration::CaptureManager::feature_finder_loader_
robot_calibration::FeatureFinderLoader feature_finder_loader_
Definition: capture_manager.h:47
robot_calibration::ChainManager
Manages moving joints to a new pose, determining when they are settled, and returning current joint_s...
Definition: chain_manager.h:37
robot_calibration::FeatureFinderLoader::load
bool load(ros::NodeHandle &nh, FeatureFinderMap &features)
Definition: feature_finder_loader.h:48
ROS_WARN
#define ROS_WARN(...)
ROS_FATAL
#define ROS_FATAL(...)
robot_calibration::CaptureManager::moveToState
bool moveToState(const sensor_msgs::JointState &state)
Definition: capture_manager.cpp:58
robot_calibration
Calibration code lives under this namespace.
Definition: base_calibration.h:28
robot_calibration::CaptureManager::description_msg_
std_msgs::String description_msg_
Definition: capture_manager.h:44
robot_calibration::CaptureManager::urdf_pub_
ros::Publisher urdf_pub_
Definition: capture_manager.h:43
robot_calibration::CaptureManager::chain_manager_
robot_calibration::ChainManager * chain_manager_
Definition: capture_manager.h:46
ros::NodeHandle


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