Go to the documentation of this file.
39 #ifndef SICK_TIM3XX_COMMON_H_
40 #define SICK_TIM3XX_COMMON_H_
49 #include <sensor_msgs/LaserScan.h>
50 #include <std_msgs/String.h>
55 #include <dynamic_reconfigure/server.h>
56 #include <sick_tim/SickTimConfig.h>
71 void update_config(sick_tim::SickTimConfig &new_config, uint32_t level = 0);
92 virtual int sendSOPASCommand(
const char* request, std::vector<unsigned char> * reply) = 0;
100 virtual int get_datagram(
unsigned char* receiveBuffer,
int bufferSize,
int* actual_length) = 0;
107 static std::string
replyToString(
const std::vector<unsigned char> &reply);
ros::Publisher datagram_pub_
virtual int init_scanner()
virtual int close_device()=0
diagnostic_updater::Updater diagnostics_
diagnostic_updater::DiagnosedPublisher< sensor_msgs::LaserScan > * diagnosticPub_
SickTimCommon(AbstractParser *parser)
virtual int get_datagram(unsigned char *receiveBuffer, int bufferSize, int *actual_length)=0
Read a datagram from the device.
double get_expected_frequency() const
bool isCompatibleDevice(const std::string identStr) const
virtual int init_device()=0
virtual bool rebootScanner()
Send a SOPAS command to the scanner that should cause a soft reset.
dynamic_reconfigure::Server< sick_tim::SickTimConfig > dynamic_reconfigure_server_
void update_config(sick_tim::SickTimConfig &new_config, uint32_t level=0)
static std::string replyToString(const std::vector< unsigned char > &reply)
Converts reply from sendSOPASCommand to string.
double expectedFrequency_
virtual int sendSOPASCommand(const char *request, std::vector< unsigned char > *reply)=0
Send a SOPAS command to the device and print out the response to the console.
virtual int stop_scanner()
void check_angle_range(SickTimConfig &conf)
sick_tim
Author(s): Jochen Sprickerhof
, Martin Günther , Sebastian Pütz
autogenerated on Thu Nov 28 2024 03:03:33