#include <MultiJointTrackerNode.h>
Public Member Functions | |
virtual void | measurementCallback (const boost::shared_ptr< ks_measurement_ros_t const > &poses_and_vels) |
Callback for the measurements for this RE level (Poses and vels of the tracker RB from the lower level, RBT) More... | |
MultiJointTrackerNode () | |
virtual bool | publishURDF (joint_tracker::publish_urdf::Request &request, joint_tracker::publish_urdf::Response &response) |
void | ReadBag () |
void | ReadParameters () |
virtual void | statePredictionCallback (const boost::shared_ptr< ks_state_ros_t const > &predicted_next_state) |
Callback for the predictions about the state of this RE level coming from the higher level of the hierarchy. More... | |
virtual | ~MultiJointTrackerNode () |
Public Member Functions inherited from omip::RecursiveEstimatorNodeInterface< ks_measurement_ros_t, ks_state_ros_t, MultiJointTracker > | |
bool | getROSParameter (std::string param_name, T ¶m_container) |
bool | getROSParameter (std::string param_name, T ¶m_container, const T &default_value) |
virtual void | measurementCallback (const boost::shared_ptr< MeasurementTypeROS const > &measurement)=0 |
virtual void | quitCallback (const std_msgs::EmptyConstPtr &msg) |
RecursiveEstimatorNodeInterface (int num_external_state_predictors) | |
virtual void | run () |
virtual void | spinStatePredictorQueue (int state_prediction_queue_idx) |
virtual void | statePredictionCallback (const boost::shared_ptr< StateTypeROS const > &predicted_next_state)=0 |
virtual | ~RecursiveEstimatorNodeInterface () |
Protected Member Functions | |
virtual void | _generateURDF (std_msgs::String &urdf_string_msg, sensor_msgs::JointState &joint_state_msg) const |
virtual void | _PrintResults () const |
Print the results of the joint tracker on the terminal. More... | |
virtual void | _publishPredictedMeasurement () const |
Publish the prediction about the next measurement by this RE level. More... | |
virtual void | _publishState () const |
Publish the current state of this RE level. More... | |
Definition at line 70 of file MultiJointTrackerNode.h.
MultiJointTrackerNode::MultiJointTrackerNode | ( | ) |
Constructor
Definition at line 36 of file MultiJointTrackerNode.cpp.
|
virtual |
Destructor
Definition at line 65 of file MultiJointTrackerNode.cpp.
|
protectedvirtual |
Definition at line 312 of file MultiJointTrackerNode.cpp.
|
protectedvirtual |
Print the results of the joint tracker on the terminal.
Definition at line 664 of file MultiJointTrackerNode.cpp.
|
protectedvirtual |
Publish the prediction about the next measurement by this RE level.
Implements omip::RecursiveEstimatorNodeInterface< ks_measurement_ros_t, ks_state_ros_t, MultiJointTracker >.
Definition at line 656 of file MultiJointTrackerNode.cpp.
|
protectedvirtual |
Publish the current state of this RE level.
Implements omip::RecursiveEstimatorNodeInterface< ks_measurement_ros_t, ks_state_ros_t, MultiJointTracker >.
Definition at line 521 of file MultiJointTrackerNode.cpp.
|
virtual |
Callback for the measurements for this RE level (Poses and vels of the tracker RB from the lower level, RBT)
poses_and_vels | Input tracked RB poses and vels |
Definition at line 192 of file MultiJointTrackerNode.cpp.
|
virtual |
Definition at line 279 of file MultiJointTrackerNode.cpp.
|
inline |
Version to work offline. Not implemented
Definition at line 107 of file MultiJointTrackerNode.h.
void MultiJointTrackerNode::ReadParameters | ( | ) |
Read parameters to create the JointTracker
Definition at line 69 of file MultiJointTrackerNode.cpp.
|
inlinevirtual |
Callback for the predictions about the state of this RE level coming from the higher level of the hierarchy.
predicted_next_state | Predictions about the next state. Right now there is no higher lever (unused) |
Definition at line 102 of file MultiJointTrackerNode.h.
|
protected |
Definition at line 137 of file MultiJointTrackerNode.h.
|
protected |
Definition at line 146 of file MultiJointTrackerNode.h.
|
protected |
Definition at line 136 of file MultiJointTrackerNode.h.
|
protected |
Definition at line 135 of file MultiJointTrackerNode.h.
|
protected |
Definition at line 148 of file MultiJointTrackerNode.h.
|
protected |
Definition at line 142 of file MultiJointTrackerNode.h.
|
protected |
Definition at line 144 of file MultiJointTrackerNode.h.
|
protected |
Definition at line 140 of file MultiJointTrackerNode.h.
|
protected |
Definition at line 133 of file MultiJointTrackerNode.h.