17 #ifndef URG_STAMPED_URG_STAMPED_H 18 #define URG_STAMPED_URG_STAMPED_H 21 #include <sensor_msgs/LaserScan.h> 23 #include <boost/bind/bind.hpp> 24 #include <boost/format.hpp> 25 #include <boost/thread.hpp> 122 const boost::posix_time::ptime& time_read,
123 const std::string& echo_back,
124 const std::string& status,
126 const bool has_intensity);
127 void cbTMSend(
const boost::posix_time::ptime& time_send);
129 const boost::posix_time::ptime& time_read,
130 const std::string& echo_back,
131 const std::string& status,
134 const boost::posix_time::ptime& time_read,
135 const std::string& echo_back,
136 const std::string& status,
137 const std::map<std::string, std::string>& params);
139 const boost::posix_time::ptime& time_read,
140 const std::string& echo_back,
141 const std::string& status,
142 const std::map<std::string, std::string>& params);
143 void cbIISend(
const boost::posix_time::ptime& time_send);
145 const boost::posix_time::ptime& time_read,
146 const std::string& echo_back,
147 const std::string& status,
148 const std::map<std::string, std::string>& params);
150 const boost::posix_time::ptime& time_read,
151 const std::string& echo_back,
152 const std::string& status);
154 const boost::posix_time::ptime& time_read,
155 const std::string& echo_back,
156 const std::string& status);
158 const boost::posix_time::ptime& time_read,
159 const std::string& echo_back,
160 const std::string& status);
172 const boost::posix_time::ptime& time_response,
173 const uint64_t& device_timestamp);
177 void sleepRandom(
const double min,
const double max);
185 #endif // URG_STAMPED_URG_STAMPED_H
void cbTM(const boost::posix_time::ptime &time_read, const std::string &echo_back, const std::string &status, const scip2::Timestamp &time_device)
std::shared_ptr< Connection > Ptr
scip2::Protocol::Ptr scip_
scip2::Walltime< 24 > walltime_
void cbM(const boost::posix_time::ptime &time_read, const std::string &echo_back, const std::string &status, const scip2::ScanData &scan, const bool has_intensity)
double allowed_device_time_origin_diff_
bool detectDeviceTimeJump(const boost::posix_time::ptime &time_response, const uint64_t &device_timestamp)
void cbQT(const boost::posix_time::ptime &time_read, const std::string &echo_back, const std::string &status)
sensor_msgs::LaserScan msg_base_
void cbTMSend(const boost::posix_time::ptime &time_send)
void cbRS(const boost::posix_time::ptime &time_read, const std::string &echo_back, const std::string &status)
void cbPP(const boost::posix_time::ptime &time_read, const std::string &echo_back, const std::string &status, const std::map< std::string, std::string > ¶ms)
DelayEstimState delay_estim_state_
void cbRB(const boost::posix_time::ptime &time_read, const std::string &echo_back, const std::string &status)
ros::Time last_sync_time_
void cbVV(const boost::posix_time::ptime &time_read, const std::string &echo_back, const std::string &status, const std::map< std::string, std::string > ¶ms)
std::uniform_real_distribution< double > sync_interval_
ResponseErrorCount error_count_
void retryTM(const ros::TimerEvent &event=ros::TimerEvent())
std::vector< ros::Duration > on_scan_communication_delays_
std::default_random_engine random_engine_
std::list< ros::Duration > communication_delays_
double communication_delay_filter_alpha_
std::list< ros::Time > device_time_origins_
ros::Duration tm_command_interval_
boost::posix_time::ptime time_ii_request
FirstOrderHPF< double > timestamp_hpf_
ros::Timer timer_retry_tm_
boost::posix_time::ptime time_tm_request
ros::Duration estimated_communication_delay_
std::shared_ptr< Protocol > Ptr
ros::Timer timer_delay_estim_
void timeSync(const ros::TimerEvent &event=ros::TimerEvent())
bool estimated_communication_delay_init_
std::string last_measurement_state_
void delayEstimation(const ros::TimerEvent &event=ros::TimerEvent())
device_time_origin::DriftedTime device_time_origin_
void cbII(const boost::posix_time::ptime &time_read, const std::string &echo_back, const std::string &status, const std::map< std::string, std::string > ¶ms)
FirstOrderLPF< double > timestamp_lpf_
void sleepRandom(const double min, const double max)
void cbIISend(const boost::posix_time::ptime &time_send)
void errorCountIncrement(const std::string &status="")
TimestampMovingAverage timestamp_moving_average_
TimestampOutlierRemover timestamp_outlier_removal_
scip2::Connection::Ptr device_