status.cpp
Go to the documentation of this file.
1 
34 #include <multisense_ros/status.h>
35 
36 #include <multisense_ros/DeviceStatus.h>
37 
38 namespace multisense_ros {
39 
41  driver_(driver),
42  device_nh_(""),
43  status_pub_(),
44  status_timer_(),
45  subscribers_(0)
46 {
47  status_pub_ = device_nh_.advertise<multisense_ros::DeviceStatus>("status", 5,
48  std::bind(&Status::connect, this),
49  std::bind(&Status::disconnect, this));
50 
52 }
53 
55 {
56 }
57 
59 {
60  (void) event;
61 
62  if (subscribers_ <= 0)
63  return;
64 
65  if (NULL != driver_)
66  {
68 
69  if (crl::multisense::Status_Ok == driver_->getDeviceStatus(statusMessage))
70  {
71  multisense_ros::DeviceStatus deviceStatus;
72 
73  deviceStatus.time = ros::Time::now();
74  deviceStatus.uptime = ros::Time(statusMessage.uptime);
75  deviceStatus.systemOk = statusMessage.systemOk;
76  deviceStatus.laserOk = statusMessage.laserOk;
77  deviceStatus.laserMotorOk = statusMessage.laserMotorOk;
78  deviceStatus.camerasOk = statusMessage.camerasOk;
79  deviceStatus.imuOk = statusMessage.imuOk;
80  deviceStatus.externalLedsOk = statusMessage.externalLedsOk;
81  deviceStatus.processingPipelineOk = statusMessage.processingPipelineOk;
82  deviceStatus.powerSupplyTemp = statusMessage.powerSupplyTemperature;
83  deviceStatus.fpgaTemp = statusMessage.fpgaTemperature;
84  deviceStatus.leftImagerTemp = statusMessage.leftImagerTemperature;
85  deviceStatus.rightImagerTemp = statusMessage.rightImagerTemperature;
86  deviceStatus.inputVoltage = statusMessage.inputVoltage;
87  deviceStatus.inputCurrent = statusMessage.inputCurrent;
88  deviceStatus.fpgaPower = statusMessage.fpgaPower;
89  deviceStatus.logicPower = statusMessage.logicPower;
90  deviceStatus.imagerPower = statusMessage.imagerPower;
91 
92  status_pub_.publish(deviceStatus);
93  }
94 
95  }
96 }
97 
99 {
100  __sync_fetch_and_add(&subscribers_, 1);
101 }
102 
104 {
105  __sync_fetch_and_sub(&subscribers_, 1);
106 }
107 
108 
109 }
void publish(const boost::shared_ptr< M > &message) const
Status(crl::multisense::Channel *driver)
Definition: status.cpp:40
ros::Timer status_timer_
Definition: status.h:69
ros::Publisher status_pub_
Definition: status.h:64
int32_t subscribers_
Definition: status.h:80
ros::NodeHandle device_nh_
Definition: status.h:59
crl::multisense::Channel * driver_
Definition: status.h:54
void queryStatus(const ros::TimerEvent &event)
Definition: status.cpp:58
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
static CRL_CONSTEXPR Status Status_Ok
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
virtual Status getDeviceStatus(system::StatusMessage &status)=0
static Time now()


multisense_ros
Author(s):
autogenerated on Sun Mar 14 2021 02:34:55