ros_driver.cpp
Go to the documentation of this file.
1 
34 #include <multisense_ros/laser.h>
35 #include <multisense_ros/camera.h>
36 #include <multisense_ros/pps.h>
37 #include <multisense_ros/imu.h>
38 #include <multisense_ros/status.h>
40 #include <ros/ros.h>
41 
42 using namespace crl::multisense;
43 
44 int main(int argc,
45  char** argvPP)
46 {
47  ros::init(argc, argvPP, "multisense_driver");
48  ros::NodeHandle nh;
49  ros::NodeHandle nh_private_("~");
50 
51  //
52  // Get parameters from ROS/command-line
53 
54  std::string sensor_ip;
55  std::string tf_prefix;
56  int sensor_mtu;
57 
58 
59  nh_private_.param<std::string>("sensor_ip", sensor_ip, "10.66.171.21");
60  nh_private_.param<std::string>("tf_prefix", tf_prefix, "multisense");
61  nh_private_.param<int>("sensor_mtu", sensor_mtu, 7200);
62 
63  Channel *d = NULL;
64 
65  try {
66 
67  d = Channel::Create(sensor_ip);
68  if (NULL == d) {
69  ROS_ERROR("multisense_ros: failed to create communication channel to sensor @ \"%s\"",
70  sensor_ip.c_str());
71  return -2;
72  }
73 
74  Status status = d->setMtu(sensor_mtu);
75  if (Status_Ok != status) {
76  ROS_ERROR("multisense_ros: failed to set sensor MTU to %d: %s",
77  sensor_mtu, Channel::statusString(status));
79  return -3;
80  }
81 
82  //
83  // Anonymous namespace so objects can deconstruct before channel is destroyed
84  {
85  multisense_ros::Laser laser(d, tf_prefix);
86  multisense_ros::Camera camera(d, tf_prefix);
87  multisense_ros::Pps pps(d);
88  multisense_ros::Imu imu(d, tf_prefix);
89  multisense_ros::Status status(d);
91  boost::bind(&multisense_ros::Camera::resolutionChanged, &camera),
92  boost::bind(&multisense_ros::Camera::borderClipChanged, &camera, _1, _2));
93  ros::spin();
94  }
95 
97  return 0;
98 
99  } catch (const std::exception& e) {
100  ROS_ERROR("multisense_ros: caught exception: %s", e.what());
101  Channel::Destroy(d);
102  return -4;
103  }
104 }
d
static const char * statusString(Status status)
static Channel * Create(const std::string &sensorAddress)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void borderClipChanged(int borderClipType, double borderClipValue)
Definition: camera.cpp:2114
ROSCPP_DECL void spin(Spinner &spinner)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
static CRL_CONSTEXPR Status Status_Ok
int main(int argc, char **argvPP)
Definition: ros_driver.cpp:44
void resolutionChanged()
Definition: camera.h:59
static void Destroy(Channel *instanceP)
int32_t Status
#define ROS_ERROR(...)


multisense_ros
Author(s):
autogenerated on Sat Apr 6 2019 02:16:53