Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039 #include "sicks300.h"
00040
00041 #include "termios.h"
00042
00043 SickS300::SickS300()
00044 {
00045
00046 ros::NodeHandle param_node("~");
00047 ros::NodeHandle nodeHandle("/");
00048
00049 int param;
00050 double x, y, z;
00051
00052
00053 param_node.param(std::string("frame"), scan_data_.header.frame_id, std::string("base_laser_link"));
00054 param_node.param(std::string("send_transform"), param, 1);
00055 if (param)
00056 {
00057 send_transform_ = true;
00058 }
00059 else
00060 {
00061 send_transform_ = false;
00062 }
00063 param_node.param(std::string("tf_x"), x, 0.115);
00064 param_node.param(std::string("tf_y"), y, 0.0);
00065 param_node.param(std::string("tf_z"), z, 0.21);
00066
00067 transform_vector_ = tf::Vector3(x, y, z);
00068
00069
00070 param_node.param(std::string("reduced_fov"), param, 0);
00071 if (param != 0)
00072 {
00073 reduced_FOV_ = true;
00074 ROS_INFO("INFO: Starting Sick300-Laser with reduced field ov view of 180 degree");
00075 }
00076 else
00077 {
00078 reduced_FOV_ = false;
00079 }
00080
00081 if (!reduced_FOV_)
00082 {
00083 scan_data_.angle_min = -135.f / 180.f * M_PI;
00084 scan_data_.angle_max = 135.f / 180.f * M_PI;
00085 scan_data_.angle_increment = 0.5f / 180.f * M_PI;
00086 scan_data_.time_increment = 0;
00087 scan_data_.scan_time = 0.08;
00088 scan_data_.range_min = 0.1;
00089 scan_data_.range_max = 29.0;
00090 scan_data_.ranges.resize(541);
00091 scan_data_.intensities.resize(541);
00092 }
00093 else
00094 {
00095 scan_data_.angle_min = -90.f / 180.f * M_PI;
00096 scan_data_.angle_max = 90.f / 180.f * M_PI;
00097 scan_data_.angle_increment = 0.5f / 180.f * M_PI;
00098 scan_data_.time_increment = 0;
00099 scan_data_.scan_time = 0.08;
00100 scan_data_.range_min = 0.1;
00101 scan_data_.range_max = 29.0;
00102 scan_data_.ranges.resize(361);
00103 scan_data_.intensities.resize(361);
00104 }
00105
00106
00107 param_node.param(std::string("devicename"), device_name_, std::string("/dev/sick300"));
00108 param_node.param(std::string("baudrate"), baud_rate_, 500000);
00109
00110 connected_ = serial_comm_.connect(device_name_, baud_rate_);
00111
00112 scan_data_publisher_ = nodeHandle.advertise<sensor_msgs::LaserScan> ("laserscan", 10);
00113
00114 }
00115
00116 SickS300::~SickS300()
00117 {
00118 }
00119
00120 void SickS300::update()
00121 {
00122
00123 if (connected_ != 0)
00124 {
00125 connected_ = serial_comm_.connect(device_name_, baud_rate_);
00126 }
00127
00128 if (connected_ == 0 && serial_comm_.readData() == 0)
00129 {
00130
00131 float* ranges = serial_comm_.getRanges();
00132 unsigned int numRanges = serial_comm_.getNumRanges();
00133 if (!reduced_FOV_)
00134 {
00135 scan_data_.ranges.resize(numRanges);
00136 for (unsigned int i = 0; i < numRanges; i++)
00137 scan_data_.ranges[i] = ranges[i];
00138 }
00139 else
00140 {
00141 for (unsigned int i = 0; i < 361; i++)
00142 scan_data_.ranges[i] = ranges[i + 89];
00143 }
00144 scan_data_.header.stamp = ros::Time::now();
00145
00146 scan_data_publisher_.publish(scan_data_);
00147
00148 }
00149
00150 }
00151
00152 void SickS300::broadcast_transform()
00153 {
00154 if (send_transform_)
00155 {
00156 tf_broadcaster_.sendTransform(tf::StampedTransform(tf::Transform(tf::Quaternion(0, 0, 0, 1), transform_vector_),
00157 ros::Time::now(), "base_link", "base_laser_link"));
00158 }
00159
00160 }
00161
00162 int main(int argc, char** argv)
00163 {
00164
00165 ros::init(argc, argv, "sicks300");
00166 ros::Time::init();
00167 ros::Rate loop_rate(20);
00168
00169 ROS_INFO("Opening connection to Sick300-Laser...");
00170
00171 SickS300 sickS300;
00172
00173 ROS_INFO("Sick300 connected.");
00174
00175 while (ros::ok())
00176 {
00177
00178 sickS300.update();
00179 sickS300.broadcast_transform();
00180
00181 ros::spinOnce();
00182 loop_rate.sleep();
00183 }
00184
00185 ROS_INFO("Laser shut down.");
00186
00187 return 0;
00188 }
00189