Classes | Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes | List of all members
urg_stamped::UrgStampedNode Class Reference

#include <urg_stamped.h>

Classes

struct  ResponseErrorCount
 

Public Member Functions

void spin ()
 
 UrgStampedNode ()
 

Protected Types

enum  DelayEstimState {
  DelayEstimState::IDLE, DelayEstimState::STOPPING_SCAN, DelayEstimState::STATE_CHECKING, DelayEstimState::ESTIMATION_STARTING,
  DelayEstimState::ESTIMATING, DelayEstimState::EXITING
}
 

Protected Member Functions

void cbClose ()
 
void cbConnect ()
 
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 > &params)
 
void cbIISend (const boost::posix_time::ptime &time_send)
 
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)
 
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 > &params)
 
void cbQT (const boost::posix_time::ptime &time_read, const std::string &echo_back, const std::string &status)
 
void cbRB (const boost::posix_time::ptime &time_read, const std::string &echo_back, const std::string &status)
 
void cbRS (const boost::posix_time::ptime &time_read, const std::string &echo_back, const std::string &status)
 
void cbSyncStart (const std_msgs::Header::ConstPtr &msg)
 
void cbTM (const boost::posix_time::ptime &time_read, const std::string &echo_back, const std::string &status, const scip2::Timestamp &time_device)
 
void cbTMSend (const boost::posix_time::ptime &time_send, const std::string &cmd)
 
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 > &params)
 
void errorCountIncrement (const std::string &status="")
 
void estimateSensorClock (const ros::TimerEvent &event=ros::TimerEvent())
 
void hardReset ()
 
void publishStatus ()
 
void publishSyncStart ()
 
void retryTM (const ros::TimerEvent &event=ros::TimerEvent())
 
void sendII ()
 
void sendTM1 ()
 
void sleepRandom (const double min, const double max)
 
void softReset ()
 
void timeSync (const ros::TimerEvent &event=ros::TimerEvent())
 

Protected Attributes

ros::Duration clock_estim_interval_
 
bool cmd_resetting_
 
DelayEstimState delay_estim_state_
 
scip2::Connection::Ptr device_
 
ResponseErrorCount error_count_
 
int error_count_max_
 
device_state_estimator::Estimator::Ptr est_
 
bool failed_
 
int fallback_on_continuous_scan_drop_
 
ros::Duration ideal_scan_interval_
 
bool is_uust2_
 
std::string last_measurement_state_
 
ros::Time last_sync_time_
 
int log_scan_drop_more_than_
 
sensor_msgs::LaserScan msg_base_
 
ros::Time next_sync_
 
ros::NodeHandle nh_
 
ros::NodeHandle pnh_
 
ros::Publisher pub_scan_
 
ros::Publisher pub_status_
 
ros::Publisher pub_sync_start_
 
bool publish_intensity_
 
std::default_random_engine random_engine_
 
int scan_drop_continuous_
 
int scan_drop_count_
 
scip2::Protocol::Ptr scip_
 
uint32_t step_max_
 
uint32_t step_min_
 
ros::Subscriber sub_sync_start_
 
std::pair< std::string, boost::posix_time::ptime > time_tm_request_
 
ros::Timer timer_retry_tm_
 
ros::Duration tm_command_interval_
 
uint32_t tm_key_
 
ros::Time tm_start_time_
 
bool tm_success_
 
int tm_try_count_
 
int tm_try_max_
 
ros::Duration uust2_stamp_offset_
 
scip2::Walltime< 24 > walltime_
 

Detailed Description

Definition at line 62 of file urg_stamped.h.

Member Enumeration Documentation

◆ DelayEstimState

Enumerator
IDLE 
STOPPING_SCAN 
STATE_CHECKING 
ESTIMATION_STARTING 
ESTIMATING 
EXITING 

Definition at line 86 of file urg_stamped.h.

Constructor & Destructor Documentation

◆ UrgStampedNode()

urg_stamped::UrgStampedNode::UrgStampedNode ( )

Definition at line 781 of file urg_stamped.cpp.

Member Function Documentation

◆ cbClose()

void urg_stamped::UrgStampedNode::cbClose ( )
protected

Definition at line 566 of file urg_stamped.cpp.

◆ cbConnect()

void urg_stamped::UrgStampedNode::cbConnect ( )
protected

Definition at line 560 of file urg_stamped.cpp.

◆ cbII()

void urg_stamped::UrgStampedNode::cbII ( const boost::posix_time::ptime &  time_read,
const std::string &  echo_back,
const std::string &  status,
const std::map< std::string, std::string > &  params 
)
protected

Definition at line 415 of file urg_stamped.cpp.

◆ cbIISend()

void urg_stamped::UrgStampedNode::cbIISend ( const boost::posix_time::ptime &  time_send)
protected

◆ cbM()

void urg_stamped::UrgStampedNode::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 
)
protected

Definition at line 48 of file urg_stamped.cpp.

◆ cbPP()

void urg_stamped::UrgStampedNode::cbPP ( const boost::posix_time::ptime &  time_read,
const std::string &  echo_back,
const std::string &  status,
const std::map< std::string, std::string > &  params 
)
protected

Definition at line 260 of file urg_stamped.cpp.

◆ cbQT()

void urg_stamped::UrgStampedNode::cbQT ( const boost::posix_time::ptime &  time_read,
const std::string &  echo_back,
const std::string &  status 
)
protected

Definition at line 480 of file urg_stamped.cpp.

◆ cbRB()

void urg_stamped::UrgStampedNode::cbRB ( const boost::posix_time::ptime &  time_read,
const std::string &  echo_back,
const std::string &  status 
)
protected

Definition at line 501 of file urg_stamped.cpp.

◆ cbRS()

void urg_stamped::UrgStampedNode::cbRS ( const boost::posix_time::ptime &  time_read,
const std::string &  echo_back,
const std::string &  status 
)
protected

Definition at line 525 of file urg_stamped.cpp.

◆ cbSyncStart()

void urg_stamped::UrgStampedNode::cbSyncStart ( const std_msgs::Header::ConstPtr &  msg)
protected

Definition at line 748 of file urg_stamped.cpp.

◆ cbTM()

void urg_stamped::UrgStampedNode::cbTM ( const boost::posix_time::ptime &  time_read,
const std::string &  echo_back,
const std::string &  status,
const scip2::Timestamp time_device 
)
protected

Definition at line 152 of file urg_stamped.cpp.

◆ cbTMSend()

void urg_stamped::UrgStampedNode::cbTMSend ( const boost::posix_time::ptime &  time_send,
const std::string &  cmd 
)
protected

Definition at line 146 of file urg_stamped.cpp.

◆ cbVV()

void urg_stamped::UrgStampedNode::cbVV ( const boost::posix_time::ptime &  time_read,
const std::string &  echo_back,
const std::string &  status,
const std::map< std::string, std::string > &  params 
)
protected

Definition at line 304 of file urg_stamped.cpp.

◆ errorCountIncrement()

void urg_stamped::UrgStampedNode::errorCountIncrement ( const std::string &  status = "")
protected

Definition at line 647 of file urg_stamped.cpp.

◆ estimateSensorClock()

void urg_stamped::UrgStampedNode::estimateSensorClock ( const ros::TimerEvent event = ros::TimerEvent())
protected

Definition at line 585 of file urg_stamped.cpp.

◆ hardReset()

void urg_stamped::UrgStampedNode::hardReset ( )
protected

Definition at line 704 of file urg_stamped.cpp.

◆ publishStatus()

void urg_stamped::UrgStampedNode::publishStatus ( )
protected

Definition at line 726 of file urg_stamped.cpp.

◆ publishSyncStart()

void urg_stamped::UrgStampedNode::publishSyncStart ( )
protected

Definition at line 773 of file urg_stamped.cpp.

◆ retryTM()

void urg_stamped::UrgStampedNode::retryTM ( const ros::TimerEvent event = ros::TimerEvent())
protected

Definition at line 606 of file urg_stamped.cpp.

◆ sendII()

void urg_stamped::UrgStampedNode::sendII ( )
protected

Definition at line 580 of file urg_stamped.cpp.

◆ sendTM1()

void urg_stamped::UrgStampedNode::sendTM1 ( )
protected

Definition at line 716 of file urg_stamped.cpp.

◆ sleepRandom()

void urg_stamped::UrgStampedNode::sleepRandom ( const double  min,
const double  max 
)
protected

Definition at line 710 of file urg_stamped.cpp.

◆ softReset()

void urg_stamped::UrgStampedNode::softReset ( )
protected

Definition at line 698 of file urg_stamped.cpp.

◆ spin()

void urg_stamped::UrgStampedNode::spin ( )

Definition at line 910 of file urg_stamped.cpp.

◆ timeSync()

void urg_stamped::UrgStampedNode::timeSync ( const ros::TimerEvent event = ros::TimerEvent())
protected

Member Data Documentation

◆ clock_estim_interval_

ros::Duration urg_stamped::UrgStampedNode::clock_estim_interval_
protected

Definition at line 85 of file urg_stamped.h.

◆ cmd_resetting_

bool urg_stamped::UrgStampedNode::cmd_resetting_
protected

Definition at line 128 of file urg_stamped.h.

◆ delay_estim_state_

DelayEstimState urg_stamped::UrgStampedNode::delay_estim_state_
protected

Definition at line 95 of file urg_stamped.h.

◆ device_

scip2::Connection::Ptr urg_stamped::UrgStampedNode::device_
protected

Definition at line 78 of file urg_stamped.h.

◆ error_count_

ResponseErrorCount urg_stamped::UrgStampedNode::error_count_
protected

Definition at line 115 of file urg_stamped.h.

◆ error_count_max_

int urg_stamped::UrgStampedNode::error_count_max_
protected

Definition at line 117 of file urg_stamped.h.

◆ est_

device_state_estimator::Estimator::Ptr urg_stamped::UrgStampedNode::est_
protected

Definition at line 130 of file urg_stamped.h.

◆ failed_

bool urg_stamped::UrgStampedNode::failed_
protected

Definition at line 82 of file urg_stamped.h.

◆ fallback_on_continuous_scan_drop_

int urg_stamped::UrgStampedNode::fallback_on_continuous_scan_drop_
protected

Definition at line 120 of file urg_stamped.h.

◆ ideal_scan_interval_

ros::Duration urg_stamped::UrgStampedNode::ideal_scan_interval_
protected

Definition at line 76 of file urg_stamped.h.

◆ is_uust2_

bool urg_stamped::UrgStampedNode::is_uust2_
protected

Definition at line 132 of file urg_stamped.h.

◆ last_measurement_state_

std::string urg_stamped::UrgStampedNode::last_measurement_state_
protected

Definition at line 124 of file urg_stamped.h.

◆ last_sync_time_

ros::Time urg_stamped::UrgStampedNode::last_sync_time_
protected

Definition at line 103 of file urg_stamped.h.

◆ log_scan_drop_more_than_

int urg_stamped::UrgStampedNode::log_scan_drop_more_than_
protected

Definition at line 121 of file urg_stamped.h.

◆ msg_base_

sensor_msgs::LaserScan urg_stamped::UrgStampedNode::msg_base_
protected

Definition at line 73 of file urg_stamped.h.

◆ next_sync_

ros::Time urg_stamped::UrgStampedNode::next_sync_
protected

Definition at line 84 of file urg_stamped.h.

◆ nh_

ros::NodeHandle urg_stamped::UrgStampedNode::nh_
protected

Definition at line 65 of file urg_stamped.h.

◆ pnh_

ros::NodeHandle urg_stamped::UrgStampedNode::pnh_
protected

Definition at line 66 of file urg_stamped.h.

◆ pub_scan_

ros::Publisher urg_stamped::UrgStampedNode::pub_scan_
protected

Definition at line 67 of file urg_stamped.h.

◆ pub_status_

ros::Publisher urg_stamped::UrgStampedNode::pub_status_
protected

Definition at line 68 of file urg_stamped.h.

◆ pub_sync_start_

ros::Publisher urg_stamped::UrgStampedNode::pub_sync_start_
protected

Definition at line 69 of file urg_stamped.h.

◆ publish_intensity_

bool urg_stamped::UrgStampedNode::publish_intensity_
protected

Definition at line 81 of file urg_stamped.h.

◆ random_engine_

std::default_random_engine urg_stamped::UrgStampedNode::random_engine_
protected

Definition at line 102 of file urg_stamped.h.

◆ scan_drop_continuous_

int urg_stamped::UrgStampedNode::scan_drop_continuous_
protected

Definition at line 119 of file urg_stamped.h.

◆ scan_drop_count_

int urg_stamped::UrgStampedNode::scan_drop_count_
protected

Definition at line 118 of file urg_stamped.h.

◆ scip_

scip2::Protocol::Ptr urg_stamped::UrgStampedNode::scip_
protected

Definition at line 79 of file urg_stamped.h.

◆ step_max_

uint32_t urg_stamped::UrgStampedNode::step_max_
protected

Definition at line 75 of file urg_stamped.h.

◆ step_min_

uint32_t urg_stamped::UrgStampedNode::step_min_
protected

Definition at line 74 of file urg_stamped.h.

◆ sub_sync_start_

ros::Subscriber urg_stamped::UrgStampedNode::sub_sync_start_
protected

Definition at line 70 of file urg_stamped.h.

◆ time_tm_request_

std::pair<std::string, boost::posix_time::ptime> urg_stamped::UrgStampedNode::time_tm_request_
protected

Definition at line 96 of file urg_stamped.h.

◆ timer_retry_tm_

ros::Timer urg_stamped::UrgStampedNode::timer_retry_tm_
protected

Definition at line 71 of file urg_stamped.h.

◆ tm_command_interval_

ros::Duration urg_stamped::UrgStampedNode::tm_command_interval_
protected

Definition at line 123 of file urg_stamped.h.

◆ tm_key_

uint32_t urg_stamped::UrgStampedNode::tm_key_
protected

Definition at line 98 of file urg_stamped.h.

◆ tm_start_time_

ros::Time urg_stamped::UrgStampedNode::tm_start_time_
protected

Definition at line 97 of file urg_stamped.h.

◆ tm_success_

bool urg_stamped::UrgStampedNode::tm_success_
protected

Definition at line 116 of file urg_stamped.h.

◆ tm_try_count_

int urg_stamped::UrgStampedNode::tm_try_count_
protected

Definition at line 126 of file urg_stamped.h.

◆ tm_try_max_

int urg_stamped::UrgStampedNode::tm_try_max_
protected

Definition at line 125 of file urg_stamped.h.

◆ uust2_stamp_offset_

ros::Duration urg_stamped::UrgStampedNode::uust2_stamp_offset_
protected

Definition at line 133 of file urg_stamped.h.

◆ walltime_

scip2::Walltime<24> urg_stamped::UrgStampedNode::walltime_
protected

Definition at line 100 of file urg_stamped.h.


The documentation for this class was generated from the following files:


urg_stamped
Author(s): Atsushi Watanabe
autogenerated on Wed Dec 18 2024 03:10:57