51 const unsigned int N = goal.joint_names.size();
53 if (N != goal.tolerances.size())
55 ROS_ERROR(
"Invalid configuration for JointStatesSettler:\n" 56 " [joint_names.size() == %u] should equal [tolerances.size() == %u]",
57 goal.joint_names.size(), goal.tolerances.size());
62 tol_ = goal.tolerances;
67 std::ostringstream info;
68 ROS_DEBUG(
"Configuring JointStatesSettler with the following joints:");
69 for (
unsigned int i=0; i<
N; i++)
80 ROS_WARN(
"Not yet configured. Going to skip");
81 return calibration_msgs::Interval();
97 sensor_msgs::JointState pruned;
void prune(const sensor_msgs::JointState &joint_states, sensor_msgs::JointState &pruned_joint_states)
Remove all the joints that we don't care about.
bool configure(const joint_states_settler::ConfigGoal &goal)
calibration_msgs::Interval add(const sensor_msgs::JointStateConstPtr msg)
void setMaxSize(unsigned int max_size)
void deflate(const sensor_msgs::JointStateConstPtr &joint_states, DeflatedJointStates &deflated_elem)
Perform the deflation on a joint_states message.
sensor_msgs::JointState pruneJointState(const sensor_msgs::JointStateConstPtr msg)
#define ROS_DEBUG_STREAM(args)
std::vector< double > tol_
void setDeflationJointNames(std::vector< std::string > joint_names)
Specify which joints to extract.
static const unsigned int N
static calibration_msgs::Interval computeLatestInterval(const SortedDeque< DeflatedConstPtr > &signal, const std::vector< double > &tolerances, ros::Duration max_spacing)
JointStatesDeflater deflater_