#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 () | |
Public Member Functions inherited from pr2_controller_interface::Controller | |
Controller () | |
bool | getController (const std::string &name, int sched, ControllerType *&c) |
bool | initRequest (ControllerProvider *cp, pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n) |
bool | isRunning () |
void | starting (const ros::Time &time) |
virtual void | starting () |
bool | startRequest () |
void | stopping (const ros::Time &time) |
virtual void | stopping () |
bool | stopRequest () |
void | update (const ros::Time &time, const ros::Duration &period) |
void | updateRequest () |
virtual | ~Controller () |
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. More... | |
bool | need_to_send_msg_ |
Tracks whether we still need to send out the m_scanner_signal_ message. More... | |
ros::NodeHandle | node_ |
int | prev_profile_segment_ |
The segment in the current profile when update() was last called. More... | |
realtime_tools::RealtimePublisher< pr2_msgs::LaserScannerSignal > * | publisher_ |
Publishes the m_scanner_signal msg from the update() realtime loop. More... | |
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_ |
Additional Inherited Members | |
Public Attributes inherited from pr2_controller_interface::Controller | |
std::vector< std::string > | after_list_ |
AFTER_ME | |
std::vector< std::string > | before_list_ |
BEFORE_ME | |
CONSTRUCTED | |
INITIALIZED | |
RUNNING | |
enum pr2_controller_interface::Controller:: { ... } | state_ |
Definition at line 120 of file laser_scanner_traj_controller.h.
LaserScannerTrajControllerNode::LaserScannerTrajControllerNode | ( | ) |
Definition at line 400 of file laser_scanner_traj_controller.cpp.
LaserScannerTrajControllerNode::~LaserScannerTrajControllerNode | ( | ) |
Definition at line 407 of file laser_scanner_traj_controller.cpp.
|
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.
|
virtual |
Implements pr2_controller_interface::Controller.
Definition at line 417 of file laser_scanner_traj_controller.cpp.
|
private |
Definition at line 147 of file laser_scanner_traj_controller.h.
|
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.
|
private |
Tracks whether we still need to send out the m_scanner_signal_ message.
Definition at line 156 of file laser_scanner_traj_controller.h.
|
private |
Definition at line 141 of file laser_scanner_traj_controller.h.
|
private |
The segment in the current profile when update() was last called.
Definition at line 151 of file laser_scanner_traj_controller.h.
|
private |
Publishes the m_scanner_signal msg from the update() realtime loop.
Definition at line 157 of file laser_scanner_traj_controller.h.
|
private |
Definition at line 148 of file laser_scanner_traj_controller.h.
|
private |
Definition at line 144 of file laser_scanner_traj_controller.h.
|
private |
Definition at line 145 of file laser_scanner_traj_controller.h.
|
private |
Definition at line 149 of file laser_scanner_traj_controller.h.
|
private |
Definition at line 142 of file laser_scanner_traj_controller.h.
|
private |
Definition at line 143 of file laser_scanner_traj_controller.h.
|
private |
Definition at line 153 of file laser_scanner_traj_controller.h.