35 #include <std_msgs/Time.h>    37 #include <multisense_ros/StampedPps.h>    48 void ppsCB(
const pps::Header& header, 
void* userDataP)
    49 { 
reinterpret_cast<Pps*
>(userDataP)->ppsCallback(header); }
    63     if (Status_Ok != status) {
    64         ROS_ERROR(
"Camera: failed to query device info: %s",
    65                   Channel::statusString(status));
    70         ROS_INFO(
"hardware does not support PPS");
    76         ROS_ERROR(
"PPS support requires sensor firmware v2.2 or greater (sensor is running v%d.%d)\n",
   107     std_msgs::Time pps_msg;
   109     multisense_ros::StampedPps stamped_pps_msg;
   115     stamped_pps_msg.data = pps_msg.data;
 
ros::NodeHandle device_nh_
crl::multisense::Channel * driver_
virtual Status getVersionInfo(system::VersionInfo &v)=0
void publish(const boost::shared_ptr< M > &message) const
virtual Status removeIsolatedCallback(image::Callback callback)=0
virtual Status addIsolatedCallback(image::Callback callback, DataSource imageSourceMask, void *userDataP=NULL)=0
uint32_t hardwareRevision
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
VersionType sensorFirmwareVersion
void ppsCallback(const crl::multisense::pps::Header &header)
virtual Status getDeviceInfo(system::DeviceInfo &info)=0
ros::Publisher stamped_pps_pub_