38 #include <diagnostic_msgs/DiagnosticStatus.h>    39 #include <urg_node/Status.h>    86   if (publish_multiecho_)
   130       if (
urg_->getAR00Status(status))
   132         urg_node::Status 
msg;
   142         if (
urg_->getDL00Status(report))
   144           msg.area_number = report.
area;
   146           msg.angle = report.
angle;
   150            ROS_WARN(
"Failed to get detection report.");
   159         ROS_WARN(
"Failed to retrieve status");
   161         urg_node::Status 
msg;
   171   ROS_INFO(
"Got update lidar status callback");
   173   res.message = 
"Laser not ready";
   177     res.message = 
"Status retrieved";
   182     res.message = 
"Failed to update status";
   193     ROS_ERROR(
"Reconfigure failed, not ready");
   199     urg_->setAngleLimitsAndCluster(config.angle_min, config.angle_max, config.cluster);
   200     urg_->setSkip(config.skip);
   205     ROS_INFO(
"Stopped data due to reconfigure.");
   208     urg_->setAngleLimitsAndCluster(config.angle_min, config.angle_max, config.cluster);
   209     urg_->setSkip(config.skip);
   214       ROS_INFO(
"Streaming data after reconfigure.");
   216     catch (std::runtime_error& e)
   227   freq_min_ = 1.0 / (
urg_->getScanPeriod() * (config.skip + 1));
   229   std::string frame_id = 
tf::resolve(config.tf_prefix, config.frame_id);
   230   urg_->setFrameId(frame_id);
   231   urg_->setUserLatency(config.time_offset);
   244   urg_node::URGConfig 
min, max;
   245   srv_->getConfigMin(min);
   246   srv_->getConfigMax(max);
   248   min.angle_min = 
urg_->getAngleMinLimit();
   249   min.angle_max = min.angle_min;
   250   max.angle_max = 
urg_->getAngleMaxLimit();
   251   max.angle_min = max.angle_max;
   253   srv_->setConfigMin(min);
   254   srv_->setConfigMax(max);
   268     ROS_INFO(
"Starting calibration. This will take a few seconds.");
   269     ROS_WARN(
"Time calibration is still experimental.");
   271     ROS_INFO(
"Calibration finished. Latency is: %.4f.", latency.
toSec());
   273   catch (std::runtime_error& e)
   275     ROS_FATAL(
"Could not calibrate time offset: %s", e.what());
   288     boost::this_thread::sleep_for(boost::chrono::milliseconds(10));
   297     stat.
summary(diagnostic_msgs::DiagnosticStatus::ERROR,
   302   if (!
urg_->getIPAddress().empty())
   304     stat.
add(
"IP Address", 
urg_->getIPAddress());
   305     stat.
add(
"IP Port", 
urg_->getIPPort());
   309     stat.
add(
"Serial Port", 
urg_->getSerialPort());
   310     stat.
add(
"Serial Baud", 
urg_->getSerialBaud());
   313   if (!
urg_->isStarted())
   315     stat.
summary(diagnostic_msgs::DiagnosticStatus::ERROR,
   322     stat.
summary(diagnostic_msgs::DiagnosticStatus::ERROR,
   327     stat.
summaryf(diagnostic_msgs::DiagnosticStatus::ERROR,
   328         "Lidar reporting error code: %X",
   333     stat.
summary(diagnostic_msgs::DiagnosticStatus::ERROR,
   334         "Lidar locked out.");
   338     stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
   348   stat.
add(
"Computed Latency", 
urg_->getComputedLatency());
   349   stat.
add(
"User Time Offset", 
urg_->getUserTimeOffset());
   379     std::stringstream ss;
   380     ss << 
"Connected to";
   393     ss << 
" device with";
   396       ss << 
" intensity and";
   398     ss << 
" ID: " << 
urg_->getDeviceID();
   416   catch (std::runtime_error& e)
   422   catch (std::exception& e)
   440         boost::this_thread::sleep(boost::posix_time::milliseconds(500));
   466       srv_.reset(
new dynamic_reconfigure::Server<urg_node::URGConfig>(
pnh_));
   490     catch (std::runtime_error& e)
   513           const sensor_msgs::MultiEchoLaserScanPtr 
msg(
new sensor_msgs::MultiEchoLaserScan());
   514           if (
urg_->grabScan(msg))
   528           const sensor_msgs::LaserScanPtr 
msg(
new sensor_msgs::LaserScan());
   529           if (
urg_->grabScan(msg))
   550         boost::this_thread::sleep_for(boost::chrono::milliseconds(10));
 void calibrate_time_offset()
static LaserPublisher advertiseLaser(ros::NodeHandle &nh, uint32_t queue_size, bool latch=false)
ros::Publisher status_pub_
std::string product_name_
bool updateStatus()
Trigger an update of the lidar's status publish the latest known information about the lidar on latch...
void publish(const boost::shared_ptr< M > &message) const 
std::string protocol_version_
boost::shared_ptr< urg_node::URGCWrapper > urg_
void summary(unsigned char lvl, const std::string s)
double diagnostics_window_time_
boost::shared_ptr< diagnostic_updater::HeaderlessTopicDiagnostic > laser_freq_
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
boost::thread diagnostics_thread_
boost::shared_ptr< diagnostic_updater::Updater > diagnostic_updater_
boost::thread scan_thread_
void update_reconfigure_limits()
boost::shared_ptr< diagnostic_updater::HeaderlessTopicDiagnostic > echoes_freq_
void summaryf(unsigned char lvl, const char *format,...)
std::string resolve(const std::string &prefix, const std::string &frame_name)
std::string firmware_version_
boost::mutex lidar_mutex_
std::string device_status_
volatile bool service_yield_
#define ROS_WARN_THROTTLE(period,...)
laser_proc::LaserPublisher echoes_pub_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const 
#define ROS_ERROR_THROTTLE(period,...)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool statusCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
std::string firmware_date_
boost::shared_ptr< dynamic_reconfigure::Server< urg_node::URGConfig > > srv_
Dynamic reconfigure server. 
#define ROS_INFO_STREAM(args)
void publish(const sensor_msgs::MultiEchoLaserScan &msg) const 
diagnostic_updater::FrequencyStatusParam FrequencyStatusParam
ROSCPP_DECL void shutdown()
ros::Publisher laser_pub_
void add(const std::string &key, const T &val)
double diagnostics_tolerance_
ros::ServiceServer status_service_
ROSCPP_DECL void spinOnce()
void populateDiagnosticsStatus(diagnostic_updater::DiagnosticStatusWrapper &stat)
void run()
Start's the nodes threads to run the lidar. 
#define ROS_DEBUG_THROTTLE(period,...)
bool reconfigure_callback(urg_node::URGConfig &config, int level)