ros_driver.cpp
Go to the documentation of this file.
00001 
00034 #include <multisense_ros/laser.h>
00035 #include <multisense_ros/camera.h>
00036 #include <multisense_ros/pps.h>
00037 #include <multisense_ros/imu.h>
00038 #include <multisense_ros/reconfigure.h>
00039 #include <ros/ros.h>
00040 
00041 using namespace crl::multisense;
00042 
00043 int main(int    argc,
00044          char** argvPP)
00045 {
00046     ros::init(argc, argvPP, "multisense_driver");
00047     ros::NodeHandle nh;
00048     ros::NodeHandle nh_private_("~");
00049 
00050     //
00051     // Get parameters from ROS/command-line
00052 
00053     std::string sensor_ip;
00054     std::string tf_prefix;
00055     int         sensor_mtu;
00056 
00057 
00058     nh_private_.param<std::string>("sensor_ip", sensor_ip, "10.66.171.21");
00059     nh_private_.param<std::string>("tf_prefix", tf_prefix, "multisense");
00060     nh_private_.param<int>("sensor_mtu", sensor_mtu, 7200);
00061 
00062     Channel *d = NULL;
00063 
00064     try {
00065 
00066         d = Channel::Create(sensor_ip);
00067         if (NULL == d) {
00068             ROS_ERROR("multisense_ros: failed to create communication channel to sensor @ \"%s\"",
00069                       sensor_ip.c_str());
00070             return -2;
00071         }
00072 
00073         Status status = d->setMtu(sensor_mtu);
00074         if (Status_Ok != status) {
00075             ROS_ERROR("multisense_ros: failed to set sensor MTU to %d: %s",
00076                       sensor_mtu, Channel::statusString(status));
00077             Channel::Destroy(d);
00078             return -3;
00079         }
00080 
00081         //
00082         // Anonymous namespace so objects can deconstruct before channel is destroyed
00083         {
00084             multisense_ros::Laser        laser(d, tf_prefix);
00085             multisense_ros::Camera       camera(d, tf_prefix);
00086             multisense_ros::Pps          pps(d);
00087             multisense_ros::Imu          imu(d, tf_prefix);
00088             multisense_ros::Reconfigure  rec(d,
00089                                              boost::bind(&multisense_ros::Camera::resolutionChanged, &camera),
00090                                              boost::bind(&multisense_ros::Camera::borderClipChanged, &camera, _1, _2));
00091             ros::spin();
00092         }
00093 
00094         Channel::Destroy(d);
00095         return 0;
00096 
00097     } catch (const std::exception& e) {
00098         ROS_ERROR("multisense_ros: caught exception: %s", e.what());
00099         Channel::Destroy(d);
00100         return -4;
00101     }
00102 }


multisense_ros
Author(s):
autogenerated on Thu Aug 27 2015 14:01:22