35 #include <multisense_ros/RawLidarData.h> 36 #include <multisense_ros/RawLidarCal.h> 39 #include <arpa/inet.h> 45 const uint32_t laser_cloud_step = 16;
74 const float Laser::EXPECTED_RATE = 40.0;
84 reinterpret_cast<Laser*
>(userDataP)->scanCallback(header);
90 reinterpret_cast<Laser*
>(userDataP)->pointCloudCallback(header);
96 const std::string& tf_prefix):
100 previous_scan_time_(0.0)
110 if (Status_Ok != status) {
111 ROS_ERROR(
"Laser: failed to query device info: %s",
112 Channel::statusString(status));
117 case system::DeviceInfo::HARDWARE_REV_MULTISENSE_SL:
124 ROS_INFO(
"hardware does not support a laser");
133 frame_id_ = tf_prefix +
"/head_hokuyo_frame";
136 motor_ = tf_prefix +
"/" +
"motor";
137 spindle_ = tf_prefix +
"/" +
"spindle";
138 hokuyo_ = tf_prefix +
"/" +
"hokuyo_link";
151 if (Status_Ok != status)
152 ROS_WARN(
"could not query lidar calibration (%s), using URDF defaults",
153 Channel::statusString(status));
177 point_cloud_.header.frame_id = tf_prefix +
"/left_camera_optical_frame";
183 point_cloud_.fields[0].datatype = sensor_msgs::PointField::FLOAT32;
187 point_cloud_.fields[1].datatype = sensor_msgs::PointField::FLOAT32;
191 point_cloud_.fields[2].datatype = sensor_msgs::PointField::FLOAT32;
195 point_cloud_.fields[3].datatype = sensor_msgs::PointField::FLOAT32;
208 raw_lidar_cal_pub_ = calibration_nh.advertise<multisense_ros::RawLidarCal>(
"raw_lidar_cal", 1,
true);
209 raw_lidar_data_pub_ = calibration_nh.advertise<multisense_ros::RawLidarData>(
"raw_lidar_data", 20,
216 multisense_ros::RawLidarCal ros_msg;
219 for(uint32_t i=0; i<16; ++i)
220 ros_msg.laserToSpindle[i] = calP[i];
223 for(uint32_t i=0; i<16; ++i)
224 ros_msg.cameraToSpindleFixed[i] = calP[i];
264 boost::mutex::scoped_lock lock(
sub_lock_);
287 uint8_t *cloudP =
reinterpret_cast<uint8_t*
>(&
point_cloud_.data[0]);
288 const uint32_t pointSize = 3 *
sizeof(float);
289 const double arcRadians = 1e-6 *
static_cast<double>(header.
scanArc);
290 const double mirrorThetaStart = -arcRadians / 2.0;
295 for(uint32_t i=0; i<header.
pointCount; ++i, cloudP += laser_cloud_step) {
300 const double percent =
static_cast<double>(i) / static_cast<double>(header.
pointCount - 1);
305 const double mirrorTheta = mirrorThetaStart + percent * arcRadians;
310 const double spindleTheta = spindleAngleStart + percent * spindleAngleRange;
317 const double rangeMeters = 1e-3 *
static_cast<double>(header.
rangesP[i]);
319 tf::Vector3(rangeMeters * std::sin(mirrorTheta), 0.0,
320 rangeMeters * std::cos(mirrorTheta)));
326 const float xyz[3] = {
static_cast<float>(pointCamera.
getX()),
327 static_cast<float>(pointCamera.
getY()),
328 static_cast<float>(pointCamera.
getZ())};
330 memcpy(cloudP, &(xyz[0]), pointSize);
331 float* intensityChannel =
reinterpret_cast<float*
>(cloudP + pointSize);
332 *intensityChannel =
static_cast<float>(header.
intensitiesP[i]);
345 const ros::Time scan_time((end_absolute_time - start_absolute_time).toSec());
348 const float angle_end = 1e-6 *
static_cast<float>(header.
spindleAngleEnd);
384 const double arcRadians = 1e-6 *
static_cast<double>(header.
scanArc);
387 laser_msg_.header.stamp = start_absolute_time;
409 RawLidarData::Ptr ros_msg(
new RawLidarData);
411 ros_msg->scan_count = header.
scanId;
412 ros_msg->time_start = start_absolute_time;
413 ros_msg->time_end = end_absolute_time;
418 memcpy(&(ros_msg->distance[0]),
423 memcpy(&(ros_msg->intensity[0]),
460 spindle_rot.
setRPY(0.0, 0.0, spindle_angle);
463 return spindle_to_motor;
487 if (Status_Ok != status)
488 ROS_ERROR(
"Laser: failed to stop laser stream: %s",
489 Channel::statusString(status));
494 boost::mutex::scoped_lock lock(
sub_lock_);
504 boost::mutex::scoped_lock lock(
sub_lock_);
509 if (Status_Ok != status)
510 ROS_ERROR(
"Laser: failed to start laser stream: %s",
511 Channel::statusString(status));
virtual Status startStreams(DataSource mask)=0
tf::Transform getSpindleTransform(float spindle_angle)
sensor_msgs::JointState joint_states_
void publish(const boost::shared_ptr< M > &message) const
void defaultTfPublisher(const ros::TimerEvent &event)
crl::multisense::lidar::Calibration lidar_cal_
sensor_msgs::LaserScan laser_msg_
virtual Status stopStreams(DataSource mask)=0
float cameraToSpindleFixed[4][4]
TFSIMD_FORCE_INLINE const tfScalar & getY() const
virtual Status getLidarCalibration(lidar::Calibration &c)=0
TFSIMD_FORCE_INLINE const tfScalar & getZ() const
ros::Publisher raw_lidar_cal_pub_
ros::Publisher raw_lidar_data_pub_
virtual Status removeIsolatedCallback(image::Callback callback)=0
virtual Status addIsolatedCallback(image::Callback callback, DataSource imageSourceMask, void *userDataP=NULL)=0
tf::Transform laser_to_spindle_
void publishSpindleTransform(const float spindle_angle, const float velocity, const ros::Time &time)
crl::multisense::Channel * driver_
void setRPY(tfScalar roll, tfScalar pitch, tfScalar yaw)
ros::Publisher joint_states_pub_
uint32_t hardwareRevision
sensor_msgs::PointCloud2 point_cloud_
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
def normalize_angle(angle)
float laserToSpindle[4][4]
tf::Transform motor_to_camera_
uint32_t getNumSubscribers() const
ros::Time previous_scan_time_
TFSIMD_FORCE_INLINE const tfScalar & getX() const
virtual Status getDeviceInfo(system::DeviceInfo &info)=0
void scanCallback(const crl::multisense::lidar::Header &header)
ros::Publisher point_cloud_pub_
void pointCloudCallback(const crl::multisense::lidar::Header &header)
tf::TransformBroadcaster static_tf_broadcaster_
std::string left_camera_optical_
void publishStaticTransforms(const ros::Time &time)