sick_tim_datagram_test.cpp
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: 21.08.2013
30  *
31  * Author: Martin Günther <mguenthe@uos.de>
32  *
33  */
34 
36 
38 
39 namespace sick_tim
40 {
41 
43  parser_(parser)
44 {
45  //dynamic_reconfigure_server_.getConfigDefault(config_);
46  dynamic_reconfigure::Server<sick_tim::SickTimConfig>::CallbackType f;
47  f = boost::bind(&sick_tim::SickTimDatagramTest::update_config, this, _1, _2);
48  dynamic_reconfigure_server_.setCallback(f);
49 
50  pub_ = nh_.advertise<sensor_msgs::LaserScan>("scan_from_datagram", 1000);
51  sub_ = nh_.subscribe("datagram", 1, &SickTimDatagramTest::datagramCB, this);
52 }
53 
55 {
56  delete parser_;
57 }
58 
59 void SickTimDatagramTest::datagramCB(const std_msgs::String::ConstPtr &datagram_msg)
60 {
61  sensor_msgs::LaserScan scan_msg;
62 
63  std::vector<char> str(datagram_msg->data.begin(), datagram_msg->data.end());
64  str.push_back('\0');
65 
66  int success = parser_->parse_datagram(&str[0], datagram_msg->data.length(), config_, scan_msg);
67  if (success == ExitSuccess)
68  pub_.publish(scan_msg);
69  else
70  ROS_ERROR("parse_datagram returned %d!", success);
71 }
72 
73 void SickTimDatagramTest::check_angle_range(SickTimConfig &conf)
74 {
75  if (conf.min_ang > conf.max_ang)
76  {
77  ROS_WARN("Minimum angle must be greater than maximum angle. Adjusting min_ang.");
78  conf.min_ang = conf.max_ang;
79  }
80 }
81 
82 void SickTimDatagramTest::update_config(sick_tim::SickTimConfig &new_config, uint32_t level)
83 {
84  check_angle_range(new_config);
85  config_ = new_config;
86 }
87 
88 } /* namespace sick_tim */
89 
90 int main(int argc, char **argv)
91 {
92  ros::init(argc, argv, "sick_tim_datagram_test");
93 
96 
97  ros::spin();
98 
99  return 0;
100 }
void publish(const boost::shared_ptr< M > &message) const
f
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
XmlRpcServer s
virtual int parse_datagram(char *datagram, size_t datagram_length, SickTimConfig &config, sensor_msgs::LaserScan &msg)=0
dynamic_reconfigure::Server< sick_tim::SickTimConfig > dynamic_reconfigure_server_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
#define ROS_WARN(...)
SickTimDatagramTest(AbstractParser *parser)
ROSCPP_DECL void spin(Spinner &spinner)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void check_angle_range(SickTimConfig &conf)
parser
#define ROS_ERROR(...)
void datagramCB(const std_msgs::String::ConstPtr &msg)
void update_config(sick_tim::SickTimConfig &new_config, uint32_t level=0)


sick_tim
Author(s): Jochen Sprickerhof , Martin Günther , Sebastian Pütz
autogenerated on Tue May 7 2019 03:13:47