Go to the documentation of this file.
34 #ifndef URG_NODE_URG_C_WRAPPER_H
35 #define URG_NODE_URG_C_WRAPPER_H
42 #include <sensor_msgs/LaserScan.h>
43 #include <sensor_msgs/MultiEchoLaserScan.h>
92 URGCWrapper(
const std::string& ip_address,
const int ip_port,
93 bool& using_intensity,
bool& using_multiecho,
bool synchronize_time);
95 URGCWrapper(
const int serial_baud,
const std::string& serial_port,
96 bool& using_intensity,
bool& using_multiecho,
bool synchronize_time);
162 bool grabScan(
const sensor_msgs::LaserScanPtr&
msg);
164 bool grabScan(
const sensor_msgs::MultiEchoLaserScanPtr&
msg);
171 void initialize(
bool& using_intensity,
bool& using_multiecho,
bool synchronize_time);
203 uint16_t
checkCRC(
const char* bytes,
const uint32_t size);
247 #endif // URG_NODE_URG_C_WRAPPER_H
double getAngleMax() const
std::string getVendorName()
std::string getProtocolVersion()
bool isMultiEchoSupported()
ros::Time getSynchronizedTime(long time_stamp, long long system_time_stamp)
Get synchronized time stamp using hardware clock.
ros::Duration getTimeStampOffset(size_t num_measurements)
std::vector< long > data_
std::string getFirmwareVersion()
std::string getProductName()
std::string frame_id_
Output frame_id for each laserscan.
std::string getFirmwareDate()
ros::Duration getNativeClockOffset(size_t num_measurements)
std::string getDeviceID()
bool isIntensitySupported()
double getRangeMin() const
void setFrameId(const std::string &frame_id)
std::string sendCommand(std::string cmd)
Send an arbitrary serial command to the lidar. These commands can also be sent via the ethernet socke...
bool getAR00Status(URGStatus &status)
std::string getSensorState()
std::string getIPAddress() const
void setUserLatency(const double latency)
std::string getSerialPort() const
bool setToSCIP2()
Set the Hokuyo URG-04LX from SCIP 1.1 mode to SCIP 2.0 mode.
double getRangeMax() const
uint16_t checkCRC(const char *bytes, const uint32_t size)
calculate the crc of a given set of bytes.
double hardware_clock_adj_
int getSerialBaud() const
double getTimeIncrement() const
bool getDL00Status(UrgDetectionReport &report)
ros::Duration system_latency_
bool setAngleLimitsAndCluster(double &angle_min, double &angle_max, int cluster)
ros::Duration user_latency_
std::string getSensorStatus()
ros::Duration getUserTimeOffset() const
double getAngleMaxLimit() const
double getAngleMinLimit() const
ros::Duration computeLatency(size_t num_measurements)
bool grabScan(const sensor_msgs::LaserScanPtr &msg)
ros::Duration getComputedLatency() const
urg_measurement_type_t measurement_type_
double getAngleMin() const
URGCWrapper(const std::string &ip_address, const int ip_port, bool &using_intensity, bool &using_multiecho, bool synchronize_time)
ros::Duration getAngularTimeOffset() const
double getScanPeriod() const
std::vector< unsigned short > intensity_
void initialize(bool &using_intensity, bool &using_multiecho, bool synchronize_time)
long last_hardware_time_stamp_
double getAngleIncrement() const
urg_node
Author(s): Chad Rockey
, Mike O'Driscoll
autogenerated on Fri Oct 14 2022 02:17:53