00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023 #include <assert.h>
00024 #include <math.h>
00025 #include <iostream>
00026 #include <boost/format.hpp>
00027
00028 #include "s3000_laser/sicks3000.h"
00029 #include "ros/time.h"
00030 #include "self_test/self_test.h"
00031 #include "diagnostic_msgs/DiagnosticStatus.h"
00032 #include "diagnostic_updater/diagnostic_updater.h"
00033 #include "diagnostic_updater/update_functions.h"
00034 #include "diagnostic_updater/DiagnosticStatusWrapper.h"
00035
00036 #include "sensor_msgs/LaserScan.h"
00037
00038 #include "tf/transform_broadcaster.h"
00039 #include "s3000_laser/enable_disable.h"
00040
00041 using namespace std;
00042
00043 class s3000node {
00044
00045 private:
00046 SickS3000 *laser;
00047 sensor_msgs::LaserScan reading;
00048
00049 string port;
00050 int baud_rate;
00051
00052 self_test::TestRunner self_test_;
00053 diagnostic_updater::Updater diagnostic_;
00054
00055 ros::NodeHandle node_handle_;
00056 ros::NodeHandle private_node_handle_;
00057 ros::Publisher laser_data_pub_;
00058
00060 bool publish_tf_;
00061 tf::TransformBroadcaster laser_broadcaster;
00063 bool publish_scan_;
00064
00065 bool running;
00066
00067 int error_count_;
00068 int slow_count_;
00069 std::string was_slow_;
00070 std::string error_status_;
00072 string frame_id_;
00073 string topic_name;
00074 double desired_freq_;
00075 diagnostic_updater::FrequencyStatus freq_diag_;
00077 ros::ServiceServer enable_disable_srv_;
00078
00079 public:
00080
00081 s3000node(ros::NodeHandle h) : self_test_(), diagnostic_(),
00082 node_handle_(h), private_node_handle_("~"),
00083 error_count_(0),
00084 slow_count_(0),
00085 desired_freq_(20),
00086 freq_diag_(diagnostic_updater::FrequencyStatusParam(&desired_freq_, &desired_freq_, 0.05))
00087 {
00088 int serial_datasize;
00089 string serial_parity;
00090 float angle_min_deg, angle_max_deg, angle_increment_deg;
00091
00092 ros::NodeHandle laser_node_handle(node_handle_, "s3000_laser");
00093 private_node_handle_.param("port", port, string("/dev/ttyUSB0"));
00094 private_node_handle_.param("baud_rate", baud_rate, 500000);
00095 private_node_handle_.param<float>("range_min", reading.range_min, 0 );
00096 private_node_handle_.param<float>("range_max", reading.range_max, 40 );
00097 private_node_handle_.param<float>("angle_min", angle_min_deg, -100 );
00098 private_node_handle_.param<float>("angle_max", angle_max_deg, 100 );
00099 private_node_handle_.param<float>("angle_increment", angle_increment_deg, 0.25 );
00100 private_node_handle_.param("topic_name", topic_name, string("/scan"));
00101 private_node_handle_.param<bool> ("publish_tf", publish_tf_, false);
00102 private_node_handle_.param<bool> ("publish_scan", publish_scan_, true);
00103 private_node_handle_.param<int> ("serial_datasize", serial_datasize, 8);
00104 private_node_handle_.param<string> ("serial_parity", serial_parity, "none");
00105 laser_data_pub_ = laser_node_handle.advertise<sensor_msgs::LaserScan>(topic_name, 1);
00106 running = false;
00107 private_node_handle_.param("frame_id", frame_id_, string("/laser"));
00108
00109 reading.angle_min = deg_to_rad(angle_min_deg);
00110 reading.angle_max = deg_to_rad(angle_max_deg);
00111 reading.angle_increment = deg_to_rad(angle_increment_deg);
00112 reading.header.frame_id = frame_id_;
00113
00114 self_test_.add("Connect Test", this, &s3000node::ConnectTest);
00115
00116 diagnostic_.add( freq_diag_ );
00117 diagnostic_.add( "Laser S3000 Status", this, &s3000node::deviceStatus );
00118 ROS_INFO("s3000node: Port = %s", port.c_str());
00119 ROS_INFO("s3000node: Baudrate = %d", baud_rate);
00120
00121
00122 enable_disable_srv_ = private_node_handle_.advertiseService("enable_disable", &s3000node::EnableDisable, this);
00123
00124
00125 laser = new SickS3000( port, baud_rate, serial_parity, serial_datasize );
00126 }
00127
00128 ~s3000node()
00129 {
00130 stop();
00131 }
00132
00133 bool spin(){
00134
00135
00136 ros::Rate r(desired_freq_);
00137
00138 while (!ros::isShuttingDown())
00139 {
00140 if (start() == 0)
00141 {
00142 while(node_handle_.ok()) {
00143 getData( reading );
00144
00145 self_test_.checkTest();
00146 diagnostic_.update();
00147 ros::spinOnce();
00148 r.sleep();
00149 }
00150 } else {
00151
00152
00153 usleep(1000000);
00154 self_test_.checkTest();
00155 ros::spinOnce();
00156 }
00157 }
00158
00159 stop();
00160
00161 return true;
00162 }
00163
00164 private:
00165
00166 int start()
00167 {
00168 stop();
00169 laser->Open();
00170 diagnostic_.setHardwareID("Laser Ranger");
00171 ROS_INFO("Laser Ranger sensor initialized.");
00172 freq_diag_.clear();
00173 running = true;
00174 return(0);
00175 }
00176
00177
00178 int stop()
00179 {
00180 if(running)
00181 {
00182 laser->Close();
00183 running = false;
00184 }
00185
00186 return(0);
00187 }
00188
00189
00190 void ConnectTest(diagnostic_updater::DiagnosticStatusWrapper& status)
00191 {
00192 laser->Open();
00193 status.summary(0, "Connected successfully.");
00194 }
00195
00197 void getData(sensor_msgs::LaserScan& scan)
00198 {
00200 if ( laser->ReadLaser(scan) )
00201 {
00202 scan.header.stamp = ros::Time::now();
00203 scan.header.frame_id = frame_id_;
00204 if(publish_scan_)
00205 laser_data_pub_.publish( scan );
00206 freq_diag_.tick();
00207 }
00208 }
00209
00211 void deviceStatus(diagnostic_updater::DiagnosticStatusWrapper &status)
00212 {
00213 if (!running)
00214 status.summary(2, "Laser Ranger is stopped");
00215 else if (!was_slow_.empty())
00216 {
00217 status.summary(1, "Excessive delay");
00218 was_slow_.clear();
00219 }
00220 else{
00221
00222 status.summary(0, "Laser Ranger is running");
00223
00224 }
00225 status.add("Device", port);
00226 status.add("TF frame", frame_id_);
00227 status.add("Error count", error_count_);
00228 status.add("Excessive delay", slow_count_);
00229 status.add("Scan publication", publish_scan_);
00230 }
00231
00233 bool EnableDisable(s3000_laser::enable_disable::Request &req, s3000_laser::enable_disable::Response &res ){
00234 publish_scan_ = req.value;
00235
00236 ROS_INFO("s3000_node::EnablaDisable: Setting scan publish to %d", req.value);
00237 res.ret = true;
00238
00239 return true;
00240 }
00241 };
00242
00243
00244 int main(int argc, char** argv)
00245 {
00246 ros::init(argc, argv, "s3000_node");
00247
00248 ros::NodeHandle nh;
00249
00250 s3000node s3000n(nh);
00251 s3000n.spin();
00252
00253 return(0);
00254 }