47 ros::init(argc, argvPP,
"multisense_driver");
54 std::string sensor_ip;
55 std::string tf_prefix;
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);
69 ROS_ERROR(
"multisense_ros: failed to create communication channel to sensor @ \"%s\"",
74 Status status = d->setMtu(sensor_mtu);
76 ROS_ERROR(
"multisense_ros: failed to set sensor MTU to %d: %s",
99 }
catch (
const std::exception& e) {
100 ROS_ERROR(
"multisense_ros: caught exception: %s", e.what());
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)
ROSCPP_DECL void spin(Spinner &spinner)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
static CRL_CONSTEXPR Status Status_Ok
int main(int argc, char **argvPP)
static void Destroy(Channel *instanceP)