#include "sick_scan/sick_scan_base.h"
#include <math.h>
#include <memory>
#include <mutex>
#include <string>
#include <sstream>
#include <thread>
#include <vector>
#include <chrono>
#include <cstdarg>
#include <cstdint>
#include <sick_scan/rosconsole_simu.hpp>
#include <ros/ros.h>
#include <geometry_msgs/Point.h>
#include <geometry_msgs/Pose2D.h>
#include <geometry_msgs/TransformStamped.h>
#include <nav_msgs/Odometry.h>
#include <sensor_msgs/LaserScan.h>
#include <sensor_msgs/PointCloud.h>
#include <sensor_msgs/PointCloud2.h>
#include <sensor_msgs/Imu.h>
#include <std_msgs/String.h>
#include <std_msgs/ColorRGBA.h>
#include <visualization_msgs/Marker.h>
#include <visualization_msgs/MarkerArray.h>
#include <tf2/LinearMath/Quaternion.h>
#include <tf2_ros/transform_broadcaster.h>
#include "sick_scan/sick_scan_logging.h"
#include <sick_scan_xd/RadarScan.h>
#include <sick_scan_xd/Encoder.h>
#include <sick_scan_xd/LIDinputstateMsg.h>
#include <sick_scan_xd/LIDoutputstateMsg.h>
#include <sick_scan_xd/LFErecMsg.h>
#include <sick_scan_xd/NAVPoseData.h>
#include <sick_scan_xd/NAVLandmarkData.h>
#include <sick_scan_xd/NAVOdomVelocity.h>
#include "sick_scan_xd/ColaMsgSrv.h"
#include "sick_scan_xd/ECRChangeArrSrv.h"
#include "sick_scan_xd/LIDoutputstateSrv.h"
#include "sick_scan_xd/SCdevicestateSrv.h"
#include "sick_scan_xd/SCrebootSrv.h"
#include "sick_scan_xd/SCsoftresetSrv.h"
#include "sick_scan_xd/SickScanExitSrv.h"
#include "sick_scan_xd/GetContaminationResultSrv.h"
#include <diagnostic_updater/diagnostic_updater.h>
#include <diagnostic_updater/publisher.h>
Go to the source code of this file.
Classes | |
class | rosPublisher< T > |
class | rosServiceClient< T > |
class | rosServiceServer< T > |
class | sick_scan_xd::SickScanConfig |
Namespaces | |
sick_scan_xd | |
Macros | |
#define | __ROS_VERSION 0 |
#define | __SICK_ROS_WRAPPER_H_INCLUDED |
#define | _USE_MATH_DEFINES |
#define | diagnostic_msgs_DiagnosticStatus_ERROR (SICK_DIAGNOSTIC_STATUS::SICK_DIAG_ERROR) |
#define | diagnostic_msgs_DiagnosticStatus_OK (SICK_DIAGNOSTIC_STATUS::OK) |
#define | diagnostic_msgs_DiagnosticStatus_WARN (SICK_DIAGNOSTIC_STATUS::WARN) |
#define | ROS_CREATE_SRV_CLIENT(nh, srv, name) nh->serviceClient<srv>(name) |
#define | ROS_CREATE_SRV_SERVER(nh, srv, name, cbfunction, cbobject) nh->advertiseService(name,cbfunction,cbobject) |
#define | ros_geometry_msgs geometry_msgs |
#define | ROS_HEADER_SEQ(msgheader, value) msgheader.seq=value |
#define | ros_nav_msgs nav_msgs |
#define | ros_sensor_msgs sensor_msgs |
#define | ros_std_msgs std_msgs |
#define | ros_visualization_msgs visualization_msgs |
#define | SICK_BIG_ENDIAN 2 |
#define | SICK_LITTLE_ENDIAN 1 |
#define | sick_scan_msg sick_scan_xd |
#define | sick_scan_srv sick_scan_xd |
#define | SICK_TARGET_ENDIANESS SICK_LITTLE_ENDIAN |
#define | TARGET_IS_LITTLE_ENDIAN 0 |
Typedefs | |
typedef ros::Duration | rosDuration |
typedef ros::NodeHandle * | rosNodePtr |
typedef int | rosQoS |
typedef ros::Time | rosTime |
Functions | |
uint32_t | nsec (const rosDuration &time) |
uint32_t | nsec (const rosTime &time) |
template<typename T > | |
std::string | paramToString (const std::vector< T > ¶m_value) |
template<typename T > | |
std::string | paramToString (const T ¶m_value) |
template<typename T > | |
rosPublisher< T > | rosAdvertise (rosNodePtr nh, const std::string &topic, uint32_t queue_size=10, rosQoS qos=10) |
template<typename T > | |
void | rosDeclareParam (rosNodePtr nh, const std::string ¶m_name, const T ¶m_value) |
rosDuration | rosDurationFromSec (double seconds) |
template<typename T > | |
bool | rosGetParam (rosNodePtr nh, const std::string ¶m_name, T ¶m_value) |
uint64_t | rosNanosecTimestampNow (void) |
bool | rosOk (void) |
template<typename T > | |
void | rosPublish (rosPublisher< T > &publisher, const T &msg) |
template<typename T > | |
void | rosSetParam (rosNodePtr nh, const std::string ¶m_name, const T ¶m_value) |
void | rosShutdown (void) |
void | rosSleep (double seconds) |
void | rosSpin (rosNodePtr nh) |
void | rosSpinOnce (rosNodePtr nh) |
rosTime | rosTimeNow (void) |
double | rosTimeToSeconds (const rosTime &time) |
template<typename T > | |
std::string | rosTopicName (rosPublisher< T > &publisher) |
uint32_t | sec (const rosDuration &time) |
uint32_t | sec (const rosTime &time) |
bool | shutdownSignalReceived () |
#define __ROS_VERSION 0 |
Definition at line 82 of file sick_ros_wrapper.h.
#define __SICK_ROS_WRAPPER_H_INCLUDED |
Definition at line 67 of file sick_ros_wrapper.h.
#define _USE_MATH_DEFINES |
Definition at line 69 of file sick_ros_wrapper.h.
#define diagnostic_msgs_DiagnosticStatus_ERROR (SICK_DIAGNOSTIC_STATUS::SICK_DIAG_ERROR) |
Definition at line 126 of file sick_ros_wrapper.h.
#define diagnostic_msgs_DiagnosticStatus_OK (SICK_DIAGNOSTIC_STATUS::OK) |
Definition at line 124 of file sick_ros_wrapper.h.
#define diagnostic_msgs_DiagnosticStatus_WARN (SICK_DIAGNOSTIC_STATUS::WARN) |
Definition at line 125 of file sick_ros_wrapper.h.
#define ROS_CREATE_SRV_CLIENT | ( | nh, | |
srv, | |||
name | |||
) | nh->serviceClient<srv>(name) |
Definition at line 249 of file sick_ros_wrapper.h.
#define ROS_CREATE_SRV_SERVER | ( | nh, | |
srv, | |||
name, | |||
cbfunction, | |||
cbobject | |||
) | nh->advertiseService(name,cbfunction,cbobject) |
Definition at line 250 of file sick_ros_wrapper.h.
#define ros_geometry_msgs geometry_msgs |
Definition at line 150 of file sick_ros_wrapper.h.
#define ROS_HEADER_SEQ | ( | msgheader, | |
value | |||
) | msgheader.seq=value |
Definition at line 162 of file sick_ros_wrapper.h.
#define ros_nav_msgs nav_msgs |
Definition at line 147 of file sick_ros_wrapper.h.
#define ros_sensor_msgs sensor_msgs |
Definition at line 148 of file sick_ros_wrapper.h.
#define ros_std_msgs std_msgs |
Definition at line 149 of file sick_ros_wrapper.h.
#define ros_visualization_msgs visualization_msgs |
Definition at line 151 of file sick_ros_wrapper.h.
#define SICK_BIG_ENDIAN 2 |
Definition at line 87 of file sick_ros_wrapper.h.
#define SICK_LITTLE_ENDIAN 1 |
Definition at line 86 of file sick_ros_wrapper.h.
#define sick_scan_msg sick_scan_xd |
Definition at line 221 of file sick_ros_wrapper.h.
#define sick_scan_srv sick_scan_xd |
Definition at line 231 of file sick_ros_wrapper.h.
#define SICK_TARGET_ENDIANESS SICK_LITTLE_ENDIAN |
Definition at line 89 of file sick_ros_wrapper.h.
#define TARGET_IS_LITTLE_ENDIAN 0 |
Definition at line 94 of file sick_ros_wrapper.h.
typedef ros::Duration rosDuration |
Definition at line 171 of file sick_ros_wrapper.h.
typedef ros::NodeHandle* rosNodePtr |
Definition at line 145 of file sick_ros_wrapper.h.
typedef int rosQoS |
Definition at line 170 of file sick_ros_wrapper.h.
Definition at line 172 of file sick_ros_wrapper.h.
|
inline |
Definition at line 177 of file sick_ros_wrapper.h.
Definition at line 175 of file sick_ros_wrapper.h.
std::string paramToString | ( | const std::vector< T > & | param_value | ) |
Definition at line 104 of file sick_ros_wrapper.h.
std::string paramToString | ( | const T & | param_value | ) |
Definition at line 111 of file sick_ros_wrapper.h.
rosPublisher<T> rosAdvertise | ( | rosNodePtr | nh, |
const std::string & | topic, | ||
uint32_t | queue_size = 10 , |
||
rosQoS | qos = 10 |
||
) |
Definition at line 187 of file sick_ros_wrapper.h.
void rosDeclareParam | ( | rosNodePtr | nh, |
const std::string & | param_name, | ||
const T & | param_value | ||
) |
Definition at line 166 of file sick_ros_wrapper.h.
|
inline |
Definition at line 211 of file sick_ros_wrapper.h.
bool rosGetParam | ( | rosNodePtr | nh, |
const std::string & | param_name, | ||
T & | param_value | ||
) |
Definition at line 167 of file sick_ros_wrapper.h.
|
inline |
Definition at line 178 of file sick_ros_wrapper.h.
|
inline |
Definition at line 206 of file sick_ros_wrapper.h.
void rosPublish | ( | rosPublisher< T > & | publisher, |
const T & | msg | ||
) |
Definition at line 203 of file sick_ros_wrapper.h.
void rosSetParam | ( | rosNodePtr | nh, |
const std::string & | param_name, | ||
const T & | param_value | ||
) |
Definition at line 168 of file sick_ros_wrapper.h.
|
inline |
Definition at line 209 of file sick_ros_wrapper.h.
|
inline |
Definition at line 210 of file sick_ros_wrapper.h.
|
inline |
Definition at line 207 of file sick_ros_wrapper.h.
|
inline |
Definition at line 208 of file sick_ros_wrapper.h.
|
inline |
Definition at line 173 of file sick_ros_wrapper.h.
Definition at line 179 of file sick_ros_wrapper.h.
std::string rosTopicName | ( | rosPublisher< T > & | publisher | ) |
Definition at line 204 of file sick_ros_wrapper.h.
|
inline |
Definition at line 176 of file sick_ros_wrapper.h.
Definition at line 174 of file sick_ros_wrapper.h.
bool shutdownSignalReceived | ( | ) |
Definition at line 206 of file sick_generic_laser.cpp.