#include <tracker.h>
Public Member Functions | |
bool | Initialize (const ros::NodeHandle &n) |
Tracker () | |
~Tracker () | |
Private Member Functions | |
bool | LoadParameters (const ros::NodeHandle &n) |
bool | PlannerDynamicsServer (typename SP::Request &req, typename SP::Response &res) |
void | PlannerStateCallback (const fastrack_msgs::State::ConstPtr &msg) |
void | ReadyCallback (const std_msgs::Empty::ConstPtr &msg) |
bool | RegisterCallbacks (const ros::NodeHandle &n) |
void | TimerCallback (const ros::TimerEvent &e) const |
void | TrackerStateCallback (const fastrack_msgs::State::ConstPtr &msg) |
bool | TrackingBoundServer (typename SB::Request &req, typename SB::Response &res) |
Private Member Functions inherited from fastrack::Uncopyable | |
Uncopyable () | |
virtual | ~Uncopyable () |
Private Attributes | |
std::string | bound_name_ |
ros::Publisher | bound_pub_ |
ros::ServiceServer | bound_srv_ |
std::string | bound_topic_ |
ros::Publisher | control_pub_ |
std::string | control_topic_ |
bool | initialized_ |
std::string | name_ |
std::string | planner_dynamics_name_ |
ros::ServiceServer | planner_dynamics_srv_ |
std::string | planner_frame_ |
ros::Subscriber | planner_state_sub_ |
std::string | planner_state_topic_ |
PS | planner_x_ |
bool | ready_ |
ros::Subscriber | ready_sub_ |
std::string | ready_topic_ |
bool | received_planner_x_ |
bool | received_tracker_x_ |
double | time_step_ |
ros::Timer | timer_ |
ros::Subscriber | tracker_state_sub_ |
std::string | tracker_state_topic_ |
TS | tracker_x_ |
V | value_ |
|
inline |
|
inlineexplicit |
bool fastrack::tracking::Tracker< V, TS, TC, PS, SB, SP >::Initialize | ( | const ros::NodeHandle & | n | ) |
|
private |
|
inlineprivate |
|
inlineprivate |
|
inlineprivate |
|
private |
|
inlineprivate |
|
inlineprivate |
|
inlineprivate |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |