Go to the documentation of this file.
22 #include <std_msgs/String.h>
34 data_pub_ = nh.
advertise<robot_calibration_msgs::CalibrationData>(
"/calibration_data", 10);
43 ROS_FATAL(
"Unable to load feature finders!");
71 robot_calibration_msgs::CalibrationData& msg)
75 if (feature_names.empty() ||
76 std::find(feature_names.begin(), feature_names.end(), it->first) != feature_names.end())
78 if (!it->second->find(&msg))
80 ROS_WARN(
"%s failed to capture features.", it->first.c_str());
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.
bool getParam(const std::string &key, bool &b) const
bool init(ros::NodeHandle &nh)
bool captureFeatures(const std::vector< std::string > &feature_names, robot_calibration_msgs::CalibrationData &msg)
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(AdvertiseOptions &ops)
bool waitToSettle()
Wait for joints to settle.
robot_calibration::FeatureFinderMap finders_
robot_calibration::FeatureFinderLoader feature_finder_loader_
Manages moving joints to a new pose, determining when they are settled, and returning current joint_s...
bool load(ros::NodeHandle &nh, FeatureFinderMap &features)
bool moveToState(const sensor_msgs::JointState &state)
Calibration code lives under this namespace.
std_msgs::String description_msg_
robot_calibration::ChainManager * chain_manager_
robot_calibration
Author(s): Michael Ferguson
autogenerated on Fri Sep 1 2023 02:52:01