#include <laser_scanner_traj_controller.h>
Public Member Functions | |
bool | init (pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n) |
LaserScannerTrajControllerNode () | |
void | setPeriodicCmd (const pr2_msgs::PeriodicCmdConstPtr &cmd) |
bool | setPeriodicSrv (pr2_msgs::SetPeriodicCmd::Request &req, pr2_msgs::SetPeriodicCmd::Response &res) |
void | setTrajCmd (const pr2_msgs::LaserTrajCmdConstPtr &traj_cmd) |
bool | setTrajSrv (pr2_msgs::SetLaserTrajCmd::Request &req, pr2_msgs::SetLaserTrajCmd::Response &res) |
void | update () |
~LaserScannerTrajControllerNode () | |
Private Attributes | |
LaserScannerTrajController | c_ |
pr2_msgs::LaserScannerSignal | m_scanner_signal_ |
Stores the message that we want to send at the end of each sweep, and halfway through each sweep. | |
bool | need_to_send_msg_ |
Tracks whether we still need to send out the m_scanner_signal_ message. | |
ros::NodeHandle | node_ |
int | prev_profile_segment_ |
The segment in the current profile when update() was last called. | |
realtime_tools::RealtimePublisher < pr2_msgs::LaserScannerSignal > * | publisher_ |
Publishes the m_scanner_signal msg from the update() realtime loop. | |
pr2_mechanism_model::RobotState * | robot_ |
ros::ServiceServer | serve_set_periodic_cmd_ |
ros::ServiceServer | serve_set_Traj_cmd_ |
std::string | service_prefix_ |
ros::Subscriber | sub_set_periodic_cmd_ |
ros::Subscriber | sub_set_traj_cmd_ |
pr2_mechanism_controllers::TrackLinkCmd | track_link_cmd_ |
Definition at line 120 of file laser_scanner_traj_controller.h.
Definition at line 400 of file laser_scanner_traj_controller.cpp.
Definition at line 407 of file laser_scanner_traj_controller.cpp.
bool LaserScannerTrajControllerNode::init | ( | pr2_mechanism_model::RobotState * | robot, |
ros::NodeHandle & | n | ||
) | [virtual] |
Implements pr2_controller_interface::Controller.
Definition at line 448 of file laser_scanner_traj_controller.cpp.
void LaserScannerTrajControllerNode::setPeriodicCmd | ( | const pr2_msgs::PeriodicCmdConstPtr & | cmd | ) |
Definition at line 501 of file laser_scanner_traj_controller.cpp.
bool LaserScannerTrajControllerNode::setPeriodicSrv | ( | pr2_msgs::SetPeriodicCmd::Request & | req, |
pr2_msgs::SetPeriodicCmd::Response & | res | ||
) |
Definition at line 486 of file laser_scanner_traj_controller.cpp.
void LaserScannerTrajControllerNode::setTrajCmd | ( | const pr2_msgs::LaserTrajCmdConstPtr & | traj_cmd | ) |
Definition at line 522 of file laser_scanner_traj_controller.cpp.
bool LaserScannerTrajControllerNode::setTrajSrv | ( | pr2_msgs::SetLaserTrajCmd::Request & | req, |
pr2_msgs::SetLaserTrajCmd::Response & | res | ||
) |
Definition at line 507 of file laser_scanner_traj_controller.cpp.
void LaserScannerTrajControllerNode::update | ( | void | ) | [virtual] |
Implements pr2_controller_interface::Controller.
Definition at line 417 of file laser_scanner_traj_controller.cpp.
Definition at line 147 of file laser_scanner_traj_controller.h.
pr2_msgs::LaserScannerSignal controller::LaserScannerTrajControllerNode::m_scanner_signal_ [private] |
Stores the message that we want to send at the end of each sweep, and halfway through each sweep.
Definition at line 155 of file laser_scanner_traj_controller.h.
Tracks whether we still need to send out the m_scanner_signal_ message.
Definition at line 156 of file laser_scanner_traj_controller.h.
Definition at line 141 of file laser_scanner_traj_controller.h.
The segment in the current profile when update() was last called.
Definition at line 151 of file laser_scanner_traj_controller.h.
realtime_tools::RealtimePublisher<pr2_msgs::LaserScannerSignal>* controller::LaserScannerTrajControllerNode::publisher_ [private] |
Publishes the m_scanner_signal msg from the update() realtime loop.
Definition at line 157 of file laser_scanner_traj_controller.h.
Definition at line 148 of file laser_scanner_traj_controller.h.
Definition at line 144 of file laser_scanner_traj_controller.h.
Definition at line 145 of file laser_scanner_traj_controller.h.
std::string controller::LaserScannerTrajControllerNode::service_prefix_ [private] |
Definition at line 149 of file laser_scanner_traj_controller.h.
Definition at line 142 of file laser_scanner_traj_controller.h.
Definition at line 143 of file laser_scanner_traj_controller.h.
pr2_mechanism_controllers::TrackLinkCmd controller::LaserScannerTrajControllerNode::track_link_cmd_ [private] |
Definition at line 153 of file laser_scanner_traj_controller.h.