Public Member Functions | |
s3000node (ros::NodeHandle h) | |
bool | spin () |
~s3000node () | |
Private Member Functions | |
void | ConnectTest (diagnostic_updater::DiagnosticStatusWrapper &status) |
void | deviceStatus (diagnostic_updater::DiagnosticStatusWrapper &status) |
Updates the diagnostic status. | |
bool | EnableDisable (s3000_laser::enable_disable::Request &req, s3000_laser::enable_disable::Response &res) |
Service callback to enable/disable scan publication. | |
void | getData (sensor_msgs::LaserScan &data) |
Gets the sensor data and publishes. | |
int | start () |
int | stop () |
Private Attributes | |
double | desired_freq_ |
diagnostic_updater::Updater | diagnostic_ |
ros::ServiceServer | enable_disable_srv_ |
Enables/disables the scan publication. | |
int | error_count_ |
std::string | error_status_ |
string | frame_id_ |
Name of the frame associated. | |
diagnostic_updater::FrequencyStatus | freq_diag_ |
SickS3000 * | laser |
tf::TransformBroadcaster | laser_broadcaster |
ros::Publisher | laser_data_pub_ |
ros::NodeHandle | node_handle_ |
string | port |
ros::NodeHandle | private_node_handle_ |
bool | publish_scan_ |
Flag to enable/disable the scan publication. | |
bool | publish_tf_ |
publish its transform to base_link | |
sensor_msgs::LaserScan | reading |
bool | running |
self_test::TestRunner | self_test_ |
int | slow_count_ |
std::string | was_slow_ |
Definition at line 43 of file s3000_laser.cc.
s3000node::s3000node | ( | ros::NodeHandle | h | ) | [inline] |
Definition at line 80 of file s3000_laser.cc.
s3000node::~s3000node | ( | ) | [inline] |
Definition at line 110 of file s3000_laser.cc.
void s3000node::ConnectTest | ( | diagnostic_updater::DiagnosticStatusWrapper & | status | ) | [inline, private] |
Definition at line 172 of file s3000_laser.cc.
void s3000node::deviceStatus | ( | diagnostic_updater::DiagnosticStatusWrapper & | status | ) | [inline, private] |
Updates the diagnostic status.
Definition at line 214 of file s3000_laser.cc.
bool s3000node::EnableDisable | ( | s3000_laser::enable_disable::Request & | req, |
s3000_laser::enable_disable::Response & | res | ||
) | [inline, private] |
Service callback to enable/disable scan publication.
Definition at line 236 of file s3000_laser.cc.
void s3000node::getData | ( | sensor_msgs::LaserScan & | data | ) | [inline, private] |
Gets the sensor data and publishes.
Definition at line 179 of file s3000_laser.cc.
bool s3000node::spin | ( | ) | [inline] |
Definition at line 115 of file s3000_laser.cc.
int s3000node::start | ( | ) | [inline, private] |
Definition at line 148 of file s3000_laser.cc.
int s3000node::stop | ( | ) | [inline, private] |
Definition at line 160 of file s3000_laser.cc.
double s3000node::desired_freq_ [private] |
Definition at line 73 of file s3000_laser.cc.
Definition at line 52 of file s3000_laser.cc.
Enables/disables the scan publication.
Definition at line 76 of file s3000_laser.cc.
int s3000node::error_count_ [private] |
Definition at line 66 of file s3000_laser.cc.
std::string s3000node::error_status_ [private] |
Definition at line 69 of file s3000_laser.cc.
string s3000node::frame_id_ [private] |
Name of the frame associated.
Definition at line 71 of file s3000_laser.cc.
Definition at line 74 of file s3000_laser.cc.
SickS3000* s3000node::laser [private] |
Definition at line 46 of file s3000_laser.cc.
Definition at line 60 of file s3000_laser.cc.
ros::Publisher s3000node::laser_data_pub_ [private] |
Definition at line 56 of file s3000_laser.cc.
ros::NodeHandle s3000node::node_handle_ [private] |
Definition at line 54 of file s3000_laser.cc.
string s3000node::port [private] |
Definition at line 49 of file s3000_laser.cc.
Definition at line 55 of file s3000_laser.cc.
bool s3000node::publish_scan_ [private] |
Flag to enable/disable the scan publication.
Definition at line 62 of file s3000_laser.cc.
bool s3000node::publish_tf_ [private] |
publish its transform to base_link
Definition at line 59 of file s3000_laser.cc.
sensor_msgs::LaserScan s3000node::reading [private] |
Definition at line 47 of file s3000_laser.cc.
bool s3000node::running [private] |
Definition at line 64 of file s3000_laser.cc.
self_test::TestRunner s3000node::self_test_ [private] |
Definition at line 51 of file s3000_laser.cc.
int s3000node::slow_count_ [private] |
Definition at line 67 of file s3000_laser.cc.
std::string s3000node::was_slow_ [private] |
Definition at line 68 of file s3000_laser.cc.