#include "sick_scan/sick_scan_base.h"
#include <algorithm>
#include <cassert>
#include <chrono>
#include <cmath>
#include <fstream>
#include <iomanip>
#include <iostream>
#include <list>
#include <map>
#include <string>
#include <sstream>
#include <thread>
#include <vector>
#include <sys/stat.h>
#include <sys/types.h>
Go to the source code of this file.
Namespaces | |
sick_scansegment_xd | |
Macros | |
#define | __SICK_SCANSEGMENT_XD_COMMON_H |
#define | _USE_MATH_DEFINES |
#define | GETCH() 0 |
#define | KBHIT() false |
#define | localtime_s(a, b) localtime_r(b,a) |
#define | SCANDATA_COMPACT 2 |
#define | SCANDATA_MSGPACK 1 |
#define | SPRINTF sprintf |
Typedefs | |
typedef std::chrono::system_clock | chrono_system_clock |
typedef std::chrono::time_point< std::chrono::system_clock > | chrono_system_time |
typedef ros_sensor_msgs::Imu | ImuMsg |
typedef rosPublisher< ImuMsg > | ImuMsgPublisher |
typedef ros_sensor_msgs::LaserScan | LaserScanMsg |
typedef rosPublisher< LaserScanMsg > | LaserscanMsgPublisher |
typedef ros_sensor_msgs::PointCloud2 | PointCloud2Msg |
typedef rosPublisher< PointCloud2Msg > | PointCloud2MsgPublisher |
typedef ros_sensor_msgs::PointField | PointField |
typedef rosTime | rosClock |
typedef int | rosQoS |
Functions | |
static std::string | sick_scansegment_xd::FilenameNoPathNoExtension (const std::string &filepath) |
static bool | sick_scansegment_xd::FileReadable (const std::string &filename) |
template<typename T > | |
static std::string | sick_scansegment_xd::FormatNumber (const T &number, int width=-1, bool setfill=false, bool setfixed=false, int precision=-1) |
static bool | sick_scansegment_xd::MkDir (const std::string &folder) |
static double | sick_scansegment_xd::Seconds (const chrono_system_time ×tamp_start, const chrono_system_time ×tamp_end=chrono_system_clock::now()) |
#define __SICK_SCANSEGMENT_XD_COMMON_H |
Definition at line 58 of file include/sick_scansegment_xd/common.h.
#define _USE_MATH_DEFINES |
Definition at line 60 of file include/sick_scansegment_xd/common.h.
#define GETCH | ( | ) | 0 |
Definition at line 87 of file include/sick_scansegment_xd/common.h.
#define KBHIT | ( | ) | false |
Definition at line 86 of file include/sick_scansegment_xd/common.h.
Definition at line 85 of file include/sick_scansegment_xd/common.h.
#define SCANDATA_COMPACT 2 |
Definition at line 93 of file include/sick_scansegment_xd/common.h.
#define SCANDATA_MSGPACK 1 |
Definition at line 92 of file include/sick_scansegment_xd/common.h.
#define SPRINTF sprintf |
Definition at line 88 of file include/sick_scansegment_xd/common.h.
typedef std::chrono::system_clock chrono_system_clock |
Definition at line 133 of file include/sick_scansegment_xd/common.h.
typedef std::chrono::time_point<std::chrono::system_clock> chrono_system_time |
Definition at line 134 of file include/sick_scansegment_xd/common.h.
typedef ros_sensor_msgs::Imu ImuMsg |
Definition at line 125 of file include/sick_scansegment_xd/common.h.
typedef rosPublisher<ImuMsg> ImuMsgPublisher |
Definition at line 126 of file include/sick_scansegment_xd/common.h.
typedef ros_sensor_msgs::LaserScan LaserScanMsg |
Definition at line 123 of file include/sick_scansegment_xd/common.h.
Definition at line 124 of file include/sick_scansegment_xd/common.h.
typedef ros_sensor_msgs::PointCloud2 PointCloud2Msg |
Definition at line 121 of file include/sick_scansegment_xd/common.h.
Definition at line 122 of file include/sick_scansegment_xd/common.h.
typedef ros_sensor_msgs::PointField PointField |
Definition at line 127 of file include/sick_scansegment_xd/common.h.
Definition at line 128 of file include/sick_scansegment_xd/common.h.
typedef int rosQoS |
Definition at line 129 of file include/sick_scansegment_xd/common.h.