#include <urg_c_wrapper.h>
Public Member Functions | |
| 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) |
| bool | 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) | |
| URGCWrapper (const int serial_baud, const std::string &serial_port, bool &using_intensity, bool &using_multiecho) | |
| ~URGCWrapper () | |
Private Member Functions | |
| uint16_t | checkCRC (const char *bytes, const uint32_t size) |
| calculate the crc of a given set of bytes. | |
| ros::Duration | getAngularTimeOffset () const |
| ros::Duration | getNativeClockOffset (size_t num_measurements) |
| ros::Duration | getTimeStampOffset (size_t num_measurements) |
| void | initialize (bool &using_intensity, bool &using_multiecho) |
| bool | isIntensitySupported () |
| bool | isMultiEchoSupported () |
| std::string | sendCommand (std::string cmd) |
| Send an arbitrary serial command to the lidar. These commands can also be sent via the ethernet socket. | |
Private Attributes | |
| int | cluster_ |
| std::vector< long > | data_ |
| int | first_step_ |
| std::string | frame_id_ |
| Output frame_id for each laserscan. | |
| std::vector< unsigned short > | intensity_ |
| std::string | ip_address_ |
| int | ip_port_ |
| int | last_step_ |
| urg_measurement_type_t | measurement_type_ |
| int | serial_baud_ |
| std::string | serial_port_ |
| int | skip_ |
| bool | started_ |
| ros::Duration | system_latency_ |
| urg_t | urg_ |
| bool | use_intensity_ |
| bool | use_multiecho_ |
| ros::Duration | user_latency_ |
Definition at line 89 of file urg_c_wrapper.h.
| urg_node::URGCWrapper::URGCWrapper | ( | const std::string & | ip_address, |
| const int | ip_port, | ||
| bool & | using_intensity, | ||
| bool & | using_multiecho | ||
| ) |
Definition at line 44 of file urg_c_wrapper.cpp.
| urg_node::URGCWrapper::URGCWrapper | ( | const int | serial_baud, |
| const std::string & | serial_port, | ||
| bool & | using_intensity, | ||
| bool & | using_multiecho | ||
| ) |
Definition at line 69 of file urg_c_wrapper.cpp.
Definition at line 184 of file urg_c_wrapper.cpp.
| uint16_t urg_node::URGCWrapper::checkCRC | ( | const char * | bytes, |
| const uint32_t | size | ||
| ) | [private] |
calculate the crc of a given set of bytes.
| bytes | The bytes array to be processed. |
| size | The size of the bytes array. |
Definition at line 523 of file urg_c_wrapper.cpp.
| ros::Duration urg_node::URGCWrapper::computeLatency | ( | size_t | num_measurements | ) |
Definition at line 874 of file urg_c_wrapper.cpp.
| double urg_node::URGCWrapper::getAngleIncrement | ( | ) | const |
Definition at line 667 of file urg_c_wrapper.cpp.
| double urg_node::URGCWrapper::getAngleMax | ( | ) | const |
Definition at line 646 of file urg_c_wrapper.cpp.
| double urg_node::URGCWrapper::getAngleMaxLimit | ( | ) | const |
Definition at line 659 of file urg_c_wrapper.cpp.
| double urg_node::URGCWrapper::getAngleMin | ( | ) | const |
Definition at line 641 of file urg_c_wrapper.cpp.
| double urg_node::URGCWrapper::getAngleMinLimit | ( | ) | const |
Definition at line 651 of file urg_c_wrapper.cpp.
| ros::Duration urg_node::URGCWrapper::getAngularTimeOffset | ( | ) | const [private] |
Definition at line 858 of file urg_c_wrapper.cpp.
| bool urg_node::URGCWrapper::getAR00Status | ( | URGStatus & | status | ) |
Definition at line 319 of file urg_c_wrapper.cpp.
Definition at line 741 of file urg_c_wrapper.cpp.
| std::string urg_node::URGCWrapper::getDeviceID | ( | ) |
Definition at line 736 of file urg_c_wrapper.cpp.
| bool urg_node::URGCWrapper::getDL00Status | ( | UrgDetectionReport & | report | ) |
Definition at line 409 of file urg_c_wrapper.cpp.
| std::string urg_node::URGCWrapper::getFirmwareDate | ( | ) |
Definition at line 726 of file urg_c_wrapper.cpp.
| std::string urg_node::URGCWrapper::getFirmwareVersion | ( | ) |
Definition at line 721 of file urg_c_wrapper.cpp.
| std::string urg_node::URGCWrapper::getIPAddress | ( | ) | const |
Definition at line 691 of file urg_c_wrapper.cpp.
| int urg_node::URGCWrapper::getIPPort | ( | ) | const |
Definition at line 696 of file urg_c_wrapper.cpp.
| ros::Duration urg_node::URGCWrapper::getNativeClockOffset | ( | size_t | num_measurements | ) | [private] |
Definition at line 904 of file urg_c_wrapper.cpp.
| std::string urg_node::URGCWrapper::getProductName | ( | ) |
Definition at line 716 of file urg_c_wrapper.cpp.
| std::string urg_node::URGCWrapper::getProtocolVersion | ( | ) |
Definition at line 731 of file urg_c_wrapper.cpp.
| double urg_node::URGCWrapper::getRangeMax | ( | ) | const |
Definition at line 633 of file urg_c_wrapper.cpp.
| double urg_node::URGCWrapper::getRangeMin | ( | ) | const |
Definition at line 625 of file urg_c_wrapper.cpp.
| double urg_node::URGCWrapper::getScanPeriod | ( | ) | const |
Definition at line 674 of file urg_c_wrapper.cpp.
| std::string urg_node::URGCWrapper::getSensorState | ( | ) |
Definition at line 756 of file urg_c_wrapper.cpp.
| std::string urg_node::URGCWrapper::getSensorStatus | ( | ) |
Definition at line 751 of file urg_c_wrapper.cpp.
| int urg_node::URGCWrapper::getSerialBaud | ( | ) | const |
Definition at line 706 of file urg_c_wrapper.cpp.
| std::string urg_node::URGCWrapper::getSerialPort | ( | ) | const |
Definition at line 701 of file urg_c_wrapper.cpp.
| double urg_node::URGCWrapper::getTimeIncrement | ( | ) | const |
Definition at line 680 of file urg_c_wrapper.cpp.
| ros::Duration urg_node::URGCWrapper::getTimeStampOffset | ( | size_t | num_measurements | ) | [private] |
Definition at line 945 of file urg_c_wrapper.cpp.
Definition at line 746 of file urg_c_wrapper.cpp.
| std::string urg_node::URGCWrapper::getVendorName | ( | ) |
Definition at line 711 of file urg_c_wrapper.cpp.
| bool urg_node::URGCWrapper::grabScan | ( | const sensor_msgs::LaserScanPtr & | msg | ) |
Definition at line 190 of file urg_c_wrapper.cpp.
| bool urg_node::URGCWrapper::grabScan | ( | const sensor_msgs::MultiEchoLaserScanPtr & | msg | ) |
Definition at line 247 of file urg_c_wrapper.cpp.
| void urg_node::URGCWrapper::initialize | ( | bool & | using_intensity, |
| bool & | using_multiecho | ||
| ) | [private] |
Definition at line 96 of file urg_c_wrapper.cpp.
| bool urg_node::URGCWrapper::isIntensitySupported | ( | ) | [private] |
Definition at line 824 of file urg_c_wrapper.cpp.
| bool urg_node::URGCWrapper::isMultiEchoSupported | ( | ) | [private] |
Definition at line 841 of file urg_c_wrapper.cpp.
| bool urg_node::URGCWrapper::isStarted | ( | ) | const |
Definition at line 620 of file urg_c_wrapper.cpp.
| 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.
| cmd | The arbitrary command fully formatted to be sent as provided |
Definition at line 530 of file urg_c_wrapper.cpp.
| bool urg_node::URGCWrapper::setAngleLimitsAndCluster | ( | double & | angle_min, |
| double & | angle_max, | ||
| int | cluster | ||
| ) |
Definition at line 772 of file urg_c_wrapper.cpp.
| void urg_node::URGCWrapper::setFrameId | ( | const std::string & | frame_id | ) |
Definition at line 761 of file urg_c_wrapper.cpp.
| bool urg_node::URGCWrapper::setSkip | ( | int | skip | ) |
Definition at line 819 of file urg_c_wrapper.cpp.
| void urg_node::URGCWrapper::setUserLatency | ( | const double | latency | ) |
Definition at line 766 of file urg_c_wrapper.cpp.
| void urg_node::URGCWrapper::start | ( | ) |
Definition at line 154 of file urg_c_wrapper.cpp.
| void urg_node::URGCWrapper::stop | ( | ) |
Definition at line 178 of file urg_c_wrapper.cpp.
int urg_node::URGCWrapper::cluster_ [private] |
Definition at line 210 of file urg_c_wrapper.h.
std::vector<long> urg_node::URGCWrapper::data_ [private] |
Definition at line 202 of file urg_c_wrapper.h.
int urg_node::URGCWrapper::first_step_ [private] |
Definition at line 208 of file urg_c_wrapper.h.
std::string urg_node::URGCWrapper::frame_id_ [private] |
Output frame_id for each laserscan.
Definition at line 197 of file urg_c_wrapper.h.
std::vector<unsigned short> urg_node::URGCWrapper::intensity_ [private] |
Definition at line 203 of file urg_c_wrapper.h.
std::string urg_node::URGCWrapper::ip_address_ [private] |
Definition at line 216 of file urg_c_wrapper.h.
int urg_node::URGCWrapper::ip_port_ [private] |
Definition at line 217 of file urg_c_wrapper.h.
int urg_node::URGCWrapper::last_step_ [private] |
Definition at line 209 of file urg_c_wrapper.h.
urg_measurement_type_t urg_node::URGCWrapper::measurement_type_ [private] |
Definition at line 207 of file urg_c_wrapper.h.
int urg_node::URGCWrapper::serial_baud_ [private] |
Definition at line 219 of file urg_c_wrapper.h.
std::string urg_node::URGCWrapper::serial_port_ [private] |
Definition at line 218 of file urg_c_wrapper.h.
int urg_node::URGCWrapper::skip_ [private] |
Definition at line 211 of file urg_c_wrapper.h.
bool urg_node::URGCWrapper::started_ [private] |
Definition at line 200 of file urg_c_wrapper.h.
Definition at line 213 of file urg_c_wrapper.h.
urg_t urg_node::URGCWrapper::urg_ [private] |
Definition at line 199 of file urg_c_wrapper.h.
bool urg_node::URGCWrapper::use_intensity_ [private] |
Definition at line 205 of file urg_c_wrapper.h.
bool urg_node::URGCWrapper::use_multiecho_ [private] |
Definition at line 206 of file urg_c_wrapper.h.
Definition at line 214 of file urg_c_wrapper.h.