sick_tim_common.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2013, Osnabrück University
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of Osnabrück University nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  *
29  * Created on: 24.05.2012
30  *
31  * Authors:
32  * Jochen Sprickerhof <jochen@sprickerhof.de>
33  * Martin Günther <mguenthe@uos.de>
34  *
35  * Based on the TiM communication example by SICK AG.
36  *
37  */
38 
39 #ifndef SICK_TIM3XX_COMMON_H_
40 #define SICK_TIM3XX_COMMON_H_
41 
42 #include <stdio.h>
43 #include <stdlib.h>
44 #include <string>
45 #include <string.h>
46 #include <vector>
47 
48 #include <ros/ros.h>
49 #include <sensor_msgs/LaserScan.h>
50 #include <std_msgs/String.h>
51 
54 
55 #include <dynamic_reconfigure/server.h>
56 #include <sick_tim/SickTimConfig.h>
57 
58 #include "abstract_parser.h"
59 
60 namespace sick_tim
61 {
62 
64 {
65 public:
67  virtual ~SickTimCommon();
68  virtual int init();
69  virtual int loopOnce();
70  void check_angle_range(SickTimConfig &conf);
71  void update_config(sick_tim::SickTimConfig &new_config, uint32_t level = 0);
72 
73  double get_expected_frequency() const { return expectedFrequency_; }
74 
76 
79  virtual bool rebootScanner();
80 
81 protected:
82  virtual int init_device() = 0;
83  virtual int init_scanner();
84  virtual int stop_scanner();
85  virtual int close_device() = 0;
86 
88 
92  virtual int sendSOPASCommand(const char* request, std::vector<unsigned char> * reply) = 0;
93 
95 
100  virtual int get_datagram(unsigned char* receiveBuffer, int bufferSize, int* actual_length) = 0;
101 
103 
107  static std::string replyToString(const std::vector<unsigned char> &reply);
108 
109  bool isCompatibleDevice(const std::string identStr) const;
110 
111 protected:
113 
114  // Dynamic Reconfigure
115  SickTimConfig config_;
118 
119  // Diagnostics
122 
123 private:
124  // ROS
127 
128 
129  dynamic_reconfigure::Server<sick_tim::SickTimConfig> dynamic_reconfigure_server_;
130 
131  // Parser
133 };
134 
135 } /* namespace sick_tim */
136 #endif /* SICK_TIM3XX_COMMON_H_ */
sick_tim::SickTimCommon::datagram_pub_
ros::Publisher datagram_pub_
Definition: sick_tim_common.h:117
ros::Publisher
sick_tim::SickTimCommon::pub_
ros::Publisher pub_
Definition: sick_tim_common.h:126
sick_tim
Definition: abstract_parser.h:41
ros.h
sick_tim::SickTimCommon::init_scanner
virtual int init_scanner()
Definition: sick_tim_common.cpp:159
sick_tim::SickTimCommon::~SickTimCommon
virtual ~SickTimCommon()
Definition: sick_tim_common.cpp:137
sick_tim::AbstractParser
Definition: abstract_parser.h:51
diagnostic_updater::Updater
abstract_parser.h
sick_tim::SickTimCommon::init
virtual int init()
Definition: sick_tim_common.cpp:145
sick_tim::SickTimCommon::loopOnce
virtual int loopOnce()
Definition: sick_tim_common.cpp:290
publisher.h
diagnostic_updater.h
sick_tim::SickTimCommon::close_device
virtual int close_device()=0
sick_tim::SickTimCommon::parser_
AbstractParser * parser_
Definition: sick_tim_common.h:132
sick_tim::SickTimCommon::diagnostics_
diagnostic_updater::Updater diagnostics_
Definition: sick_tim_common.h:112
sick_tim::SickTimCommon::diagnosticPub_
diagnostic_updater::DiagnosedPublisher< sensor_msgs::LaserScan > * diagnosticPub_
Definition: sick_tim_common.h:120
sick_tim::SickTimCommon::publish_datagram_
bool publish_datagram_
Definition: sick_tim_common.h:116
sick_tim::SickTimCommon::SickTimCommon
SickTimCommon(AbstractParser *parser)
Definition: sick_tim_common.cpp:47
sick_tim::SickTimCommon::get_datagram
virtual int get_datagram(unsigned char *receiveBuffer, int bufferSize, int *actual_length)=0
Read a datagram from the device.
diagnostic_updater::DiagnosedPublisher< sensor_msgs::LaserScan >
sick_tim::SickTimCommon::get_expected_frequency
double get_expected_frequency() const
Definition: sick_tim_common.h:73
sick_tim::SickTimCommon::isCompatibleDevice
bool isCompatibleDevice(const std::string identStr) const
Definition: sick_tim_common.cpp:270
sick_tim::SickTimCommon::init_device
virtual int init_device()=0
sick_tim::SickTimCommon::nh_
ros::NodeHandle nh_
Definition: sick_tim_common.h:125
sick_tim::SickTimCommon::rebootScanner
virtual bool rebootScanner()
Send a SOPAS command to the scanner that should cause a soft reset.
Definition: sick_tim_common.cpp:89
sick_tim::SickTimCommon::dynamic_reconfigure_server_
dynamic_reconfigure::Server< sick_tim::SickTimConfig > dynamic_reconfigure_server_
Definition: sick_tim_common.h:129
sick_tim::SickTimCommon::config_
SickTimConfig config_
Definition: sick_tim_common.h:115
sick_tim::SickTimCommon::update_config
void update_config(sick_tim::SickTimConfig &new_config, uint32_t level=0)
Definition: sick_tim_common.cpp:349
sick_tim::SickTimCommon::replyToString
static std::string replyToString(const std::vector< unsigned char > &reply)
Converts reply from sendSOPASCommand to string.
Definition: sick_tim_common.cpp:257
sick_tim::SickTimCommon
Definition: sick_tim_common.h:63
sick_tim::SickTimCommon::expectedFrequency_
double expectedFrequency_
Definition: sick_tim_common.h:121
sick_tim::SickTimCommon::sendSOPASCommand
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.
ros::NodeHandle
sick_tim::SickTimCommon::stop_scanner
virtual int stop_scanner()
Definition: sick_tim_common.cpp:73
sick_tim::SickTimCommon::check_angle_range
void check_angle_range(SickTimConfig &conf)
Definition: sick_tim_common.cpp:340


sick_tim
Author(s): Jochen Sprickerhof , Martin Günther , Sebastian Pütz
autogenerated on Thu Nov 28 2024 03:03:33