Public Member Functions | Private Attributes
controller::LaserScannerTrajControllerNode Class Reference

#include <laser_scanner_traj_controller.h>

Inheritance diagram for controller::LaserScannerTrajControllerNode:
Inheritance graph
[legend]

List of all members.

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::RobotStaterobot_
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_

Detailed Description

Definition at line 120 of file laser_scanner_traj_controller.h.


Constructor & Destructor Documentation

Definition at line 400 of file laser_scanner_traj_controller.cpp.

Definition at line 407 of file laser_scanner_traj_controller.cpp.


Member Function Documentation

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]

Member Data Documentation

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.

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.

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.


The documentation for this class was generated from the following files:


pr2_mechanism_controllers
Author(s): Sachin Chita, John Hsu, Melonee Wise
autogenerated on Thu Aug 27 2015 14:22:52