capture_manager.h
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 #ifndef ROBOT_CALIBRATION_CAPTURE_CAPTURE_MANAGER_H
22 #define ROBOT_CALIBRATION_CAPTURE_CAPTURE_MANAGER_H
23 
24 #include <string>
25 #include <vector>
28 
29 namespace robot_calibration
30 {
32 {
33 public:
35  bool init(ros::NodeHandle& nh);
36  bool moveToState(const sensor_msgs::JointState& state);
37  bool captureFeatures(const std::vector<std::string>& feature_names,
38  robot_calibration_msgs::CalibrationData& msg);
39  std::string getUrdf();
40 
41 private:
44  std_msgs::String description_msg_;
45 
49 };
50 
51 } // namespace robot_calibration
52 
53 #endif // ROBOT_CALIBRATION_CAPTURE_CAPTURE_MANAGER_H
chain_manager.h
robot_calibration::CaptureManager::CaptureManager
CaptureManager()
Definition: capture_manager.cpp:28
ros::Publisher
robot_calibration::FeatureFinderMap
std::map< std::string, FeatureFinderPtr > FeatureFinderMap
Definition: feature_finder_loader.h:35
robot_calibration::CaptureManager::getUrdf
std::string getUrdf()
Definition: capture_manager.cpp:91
robot_calibration::FeatureFinderLoader
Load feature finders, based on param server config.
Definition: feature_finder_loader.h:40
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
robot_calibration::CaptureManager
Definition: capture_manager.h:31
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::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
feature_finder_loader.h
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