|
| bool | change (trajectory_tracker_msgs::ChangePath::Request &req, trajectory_tracker_msgs::ChangePath::Response &res) |
| |
| bool | loadFile () |
| |
| void | loadPath () |
| |
| void | processFeedback (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) |
| |
| void | updateIM () |
| |
Definition at line 56 of file trajectory_server.cpp.
◆ anonymous enum
◆ ServerNode()
| ServerNode::ServerNode |
( |
| ) |
|
◆ ~ServerNode()
| ServerNode::~ServerNode |
( |
| ) |
|
◆ change()
| bool ServerNode::change |
( |
trajectory_tracker_msgs::ChangePath::Request & |
req, |
|
|
trajectory_tracker_msgs::ChangePath::Response & |
res |
|
) |
| |
|
private |
◆ loadFile()
| bool ServerNode::loadFile |
( |
| ) |
|
|
private |
◆ loadPath()
| void ServerNode::loadPath |
( |
| ) |
|
|
private |
◆ processFeedback()
| void ServerNode::processFeedback |
( |
const visualization_msgs::InteractiveMarkerFeedbackConstPtr & |
feedback | ) |
|
|
private |
◆ spin()
| void ServerNode::spin |
( |
| ) |
|
◆ updateIM()
| void ServerNode::updateIM |
( |
| ) |
|
|
private |
◆ buffer_
◆ filter_step_
| double ServerNode::filter_step_ |
|
private |
◆ hz_
◆ lpf_
◆ max_markers_
| int ServerNode::max_markers_ |
|
private |
◆ nh_
◆ path_
| nav_msgs::Path ServerNode::path_ |
|
private |
◆ pnh_
◆ pub_path_
◆ pub_status_
◆ req_path_
| trajectory_tracker_msgs::ChangePath::Request ServerNode::req_path_ |
|
private |
◆ serial_size_
| int ServerNode::serial_size_ |
|
private |
◆ srv_change_path_
◆ srv_im_fb_
◆ topic_path_
| std::string ServerNode::topic_path_ |
|
private |
◆ update_num_
| int ServerNode::update_num_ |
|
private |
The documentation for this class was generated from the following file: