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


multisense_ros
Author(s):
autogenerated on Mon Oct 9 2017 03:06:27