36 #include <multisense_ros/DeviceStatus.h>    71             multisense_ros::DeviceStatus deviceStatus;
    75             deviceStatus.systemOk = statusMessage.
systemOk;
    76             deviceStatus.laserOk = statusMessage.
laserOk;
    78             deviceStatus.camerasOk = statusMessage.
camerasOk;
    79             deviceStatus.imuOk = statusMessage.
imuOk;
    88             deviceStatus.fpgaPower = statusMessage.
fpgaPower;
    89             deviceStatus.logicPower = statusMessage.
logicPower;
    90             deviceStatus.imagerPower = statusMessage.
imagerPower;
 
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
Status(crl::multisense::Channel *driver)
float powerSupplyTemperature
ros::Publisher status_pub_
ros::NodeHandle device_nh_
void publish(const boost::shared_ptr< M > &message) const
float leftImagerTemperature
crl::multisense::Channel * driver_
void queryStatus(const ros::TimerEvent &event)
static CRL_CONSTEXPR Status Status_Ok
bool processingPipelineOk
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
virtual Status getDeviceStatus(system::StatusMessage &status)=0
float rightImagerTemperature