#include <urg_c_wrapper.h>
|
| ros::Duration | computeLatency (size_t num_measurements) |
| |
| double | getAngleIncrement () const |
| |
| double | getAngleMax () const |
| |
| double | getAngleMaxLimit () const |
| |
| double | getAngleMin () const |
| |
| double | getAngleMinLimit () const |
| |
| bool | getAR00Status (URGStatus &status) |
| |
| ros::Duration | getComputedLatency () const |
| |
| std::string | getDeviceID () |
| |
| bool | getDL00Status (UrgDetectionReport &report) |
| |
| std::string | getFirmwareDate () |
| |
| std::string | getFirmwareVersion () |
| |
| std::string | getIPAddress () const |
| |
| int | getIPPort () const |
| |
| std::string | getProductName () |
| |
| std::string | getProtocolVersion () |
| |
| double | getRangeMax () const |
| |
| double | getRangeMin () const |
| |
| double | getScanPeriod () const |
| |
| std::string | getSensorState () |
| |
| std::string | getSensorStatus () |
| |
| int | getSerialBaud () const |
| |
| std::string | getSerialPort () const |
| |
| double | getTimeIncrement () const |
| |
| ros::Duration | getUserTimeOffset () const |
| |
| std::string | getVendorName () |
| |
| bool | grabScan (const sensor_msgs::LaserScanPtr &msg) |
| |
| bool | grabScan (const sensor_msgs::MultiEchoLaserScanPtr &msg) |
| |
| bool | isStarted () const |
| |
| bool | setAngleLimitsAndCluster (double &angle_min, double &angle_max, int cluster) |
| |
| void | setFrameId (const std::string &frame_id) |
| |
| void | setSkip (int skip) |
| |
| void | setUserLatency (const double latency) |
| |
| void | start () |
| |
| void | stop () |
| |
| | URGCWrapper (const std::string &ip_address, const int ip_port, bool &using_intensity, bool &using_multiecho, bool synchronize_time) |
| |
| | URGCWrapper (const int serial_baud, const std::string &serial_port, bool &using_intensity, bool &using_multiecho, bool synchronize_time) |
| |
| | ~URGCWrapper () |
| |
Definition at line 89 of file urg_c_wrapper.h.
◆ URGCWrapper() [1/2]
| urg_node::URGCWrapper::URGCWrapper |
( |
const std::string & |
ip_address, |
|
|
const int |
ip_port, |
|
|
bool & |
using_intensity, |
|
|
bool & |
using_multiecho, |
|
|
bool |
synchronize_time |
|
) |
| |
◆ URGCWrapper() [2/2]
| urg_node::URGCWrapper::URGCWrapper |
( |
const int |
serial_baud, |
|
|
const std::string & |
serial_port, |
|
|
bool & |
using_intensity, |
|
|
bool & |
using_multiecho, |
|
|
bool |
synchronize_time |
|
) |
| |
◆ ~URGCWrapper()
| urg_node::URGCWrapper::~URGCWrapper |
( |
| ) |
|
◆ checkCRC()
| uint16_t urg_node::URGCWrapper::checkCRC |
( |
const char * |
bytes, |
|
|
const uint32_t |
size |
|
) |
| |
|
private |
calculate the crc of a given set of bytes.
- Parameters
-
| bytes | The bytes array to be processed. |
| size | The size of the bytes array. |
- Returns
- the calculated CRC of the bytes.
Definition at line 572 of file urg_c_wrapper.cpp.
◆ computeLatency()
| ros::Duration urg_node::URGCWrapper::computeLatency |
( |
size_t |
num_measurements | ) |
|
◆ getAngleIncrement()
| double urg_node::URGCWrapper::getAngleIncrement |
( |
| ) |
const |
◆ getAngleMax()
| double urg_node::URGCWrapper::getAngleMax |
( |
| ) |
const |
◆ getAngleMaxLimit()
| double urg_node::URGCWrapper::getAngleMaxLimit |
( |
| ) |
const |
◆ getAngleMin()
| double urg_node::URGCWrapper::getAngleMin |
( |
| ) |
const |
◆ getAngleMinLimit()
| double urg_node::URGCWrapper::getAngleMinLimit |
( |
| ) |
const |
◆ getAngularTimeOffset()
| ros::Duration urg_node::URGCWrapper::getAngularTimeOffset |
( |
| ) |
const |
|
private |
◆ getAR00Status()
| bool urg_node::URGCWrapper::getAR00Status |
( |
URGStatus & |
status | ) |
|
◆ getComputedLatency()
| ros::Duration urg_node::URGCWrapper::getComputedLatency |
( |
| ) |
const |
◆ getDeviceID()
| std::string urg_node::URGCWrapper::getDeviceID |
( |
| ) |
|
◆ getDL00Status()
◆ getFirmwareDate()
| std::string urg_node::URGCWrapper::getFirmwareDate |
( |
| ) |
|
◆ getFirmwareVersion()
| std::string urg_node::URGCWrapper::getFirmwareVersion |
( |
| ) |
|
◆ getIPAddress()
| std::string urg_node::URGCWrapper::getIPAddress |
( |
| ) |
const |
◆ getIPPort()
| int urg_node::URGCWrapper::getIPPort |
( |
| ) |
const |
◆ getNativeClockOffset()
| ros::Duration urg_node::URGCWrapper::getNativeClockOffset |
( |
size_t |
num_measurements | ) |
|
|
private |
◆ getProductName()
| std::string urg_node::URGCWrapper::getProductName |
( |
| ) |
|
◆ getProtocolVersion()
| std::string urg_node::URGCWrapper::getProtocolVersion |
( |
| ) |
|
◆ getRangeMax()
| double urg_node::URGCWrapper::getRangeMax |
( |
| ) |
const |
◆ getRangeMin()
| double urg_node::URGCWrapper::getRangeMin |
( |
| ) |
const |
◆ getScanPeriod()
| double urg_node::URGCWrapper::getScanPeriod |
( |
| ) |
const |
◆ getSensorState()
| std::string urg_node::URGCWrapper::getSensorState |
( |
| ) |
|
◆ getSensorStatus()
| std::string urg_node::URGCWrapper::getSensorStatus |
( |
| ) |
|
◆ getSerialBaud()
| int urg_node::URGCWrapper::getSerialBaud |
( |
| ) |
const |
◆ getSerialPort()
| std::string urg_node::URGCWrapper::getSerialPort |
( |
| ) |
const |
◆ getSynchronizedTime()
| ros::Time urg_node::URGCWrapper::getSynchronizedTime |
( |
long |
time_stamp, |
|
|
long long |
system_time_stamp |
|
) |
| |
|
private |
Get synchronized time stamp using hardware clock.
- Parameters
-
| time_stamp | The current hardware time stamp. |
| system_time_stamp | The current system time stamp. |
- Returns
- ros::Time stamp representing synchronized time
Definition at line 1052 of file urg_c_wrapper.cpp.
◆ getTimeIncrement()
| double urg_node::URGCWrapper::getTimeIncrement |
( |
| ) |
const |
◆ getTimeStampOffset()
| ros::Duration urg_node::URGCWrapper::getTimeStampOffset |
( |
size_t |
num_measurements | ) |
|
|
private |
◆ getUserTimeOffset()
◆ getVendorName()
| std::string urg_node::URGCWrapper::getVendorName |
( |
| ) |
|
◆ grabScan() [1/2]
| bool urg_node::URGCWrapper::grabScan |
( |
const sensor_msgs::LaserScanPtr & |
msg | ) |
|
◆ grabScan() [2/2]
| bool urg_node::URGCWrapper::grabScan |
( |
const sensor_msgs::MultiEchoLaserScanPtr & |
msg | ) |
|
◆ initialize()
| void urg_node::URGCWrapper::initialize |
( |
bool & |
using_intensity, |
|
|
bool & |
using_multiecho, |
|
|
bool |
synchronize_time |
|
) |
| |
|
private |
◆ isIntensitySupported()
| bool urg_node::URGCWrapper::isIntensitySupported |
( |
| ) |
|
|
private |
◆ isMultiEchoSupported()
| bool urg_node::URGCWrapper::isMultiEchoSupported |
( |
| ) |
|
|
private |
◆ isStarted()
| bool urg_node::URGCWrapper::isStarted |
( |
| ) |
const |
◆ sendCommand()
| std::string urg_node::URGCWrapper::sendCommand |
( |
std::string |
cmd | ) |
|
|
private |
Send an arbitrary serial command to the lidar. These commands can also be sent via the ethernet socket.
- Parameters
-
| cmd | The arbitrary command fully formatted to be sent as provided |
- Returns
- The textual response of the Lidar, empty if, but may return lidar's own error string.
Definition at line 579 of file urg_c_wrapper.cpp.
◆ setAngleLimitsAndCluster()
| bool urg_node::URGCWrapper::setAngleLimitsAndCluster |
( |
double & |
angle_min, |
|
|
double & |
angle_max, |
|
|
int |
cluster |
|
) |
| |
◆ setFrameId()
| void urg_node::URGCWrapper::setFrameId |
( |
const std::string & |
frame_id | ) |
|
◆ setSkip()
| void urg_node::URGCWrapper::setSkip |
( |
int |
skip | ) |
|
◆ setToSCIP2()
| bool urg_node::URGCWrapper::setToSCIP2 |
( |
| ) |
|
|
private |
Set the Hokuyo URG-04LX from SCIP 1.1 mode to SCIP 2.0 mode.
- Returns
- True if successful and false if not.
Definition at line 545 of file urg_c_wrapper.cpp.
◆ setUserLatency()
| void urg_node::URGCWrapper::setUserLatency |
( |
const double |
latency | ) |
|
◆ start()
| void urg_node::URGCWrapper::start |
( |
| ) |
|
◆ stop()
| void urg_node::URGCWrapper::stop |
( |
| ) |
|
◆ adj_alpha_
| const double urg_node::URGCWrapper::adj_alpha_ = .01 |
|
private |
◆ adj_count_
| uint64_t urg_node::URGCWrapper::adj_count_ |
|
private |
◆ cluster_
| int urg_node::URGCWrapper::cluster_ |
|
private |
◆ data_
| std::vector<long> urg_node::URGCWrapper::data_ |
|
private |
◆ first_step_
| int urg_node::URGCWrapper::first_step_ |
|
private |
◆ frame_id_
| std::string urg_node::URGCWrapper::frame_id_ |
|
private |
◆ hardware_clock_
| double urg_node::URGCWrapper::hardware_clock_ |
|
private |
◆ hardware_clock_adj_
| double urg_node::URGCWrapper::hardware_clock_adj_ |
|
private |
◆ intensity_
| std::vector<unsigned short> urg_node::URGCWrapper::intensity_ |
|
private |
◆ ip_address_
| std::string urg_node::URGCWrapper::ip_address_ |
|
private |
◆ ip_port_
| int urg_node::URGCWrapper::ip_port_ |
|
private |
◆ last_hardware_time_stamp_
| long urg_node::URGCWrapper::last_hardware_time_stamp_ |
|
private |
◆ last_step_
| int urg_node::URGCWrapper::last_step_ |
|
private |
◆ measurement_type_
◆ serial_baud_
| int urg_node::URGCWrapper::serial_baud_ |
|
private |
◆ serial_port_
| std::string urg_node::URGCWrapper::serial_port_ |
|
private |
◆ skip_
| int urg_node::URGCWrapper::skip_ |
|
private |
◆ started_
| bool urg_node::URGCWrapper::started_ |
|
private |
◆ synchronize_time_
| bool urg_node::URGCWrapper::synchronize_time_ |
|
private |
◆ system_latency_
◆ urg_
| urg_t urg_node::URGCWrapper::urg_ |
|
private |
◆ use_intensity_
| bool urg_node::URGCWrapper::use_intensity_ |
|
private |
◆ use_multiecho_
| bool urg_node::URGCWrapper::use_multiecho_ |
|
private |
◆ user_latency_
The documentation for this class was generated from the following files: