plus.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2009, Willow Garage, Inc.
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 the Willow Garage, Inc. 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 
31 #include <nodelet/nodelet.h>
32 #include <ros/ros.h>
33 #include <std_msgs/Float64.h>
34 #include <stdio.h>
35 
36 
37 #include <math.h> //fabs
38 
40 {
41 
42 class Plus : public nodelet::Nodelet
43 {
44 public:
45  Plus()
46  : value_(0)
47  {}
48 
49 private:
50  virtual void onInit()
51  {
52  ros::NodeHandle& private_nh = getPrivateNodeHandle();
53  private_nh.getParam("value", value_);
54  pub = private_nh.advertise<std_msgs::Float64>("out", 10);
55  sub = private_nh.subscribe("in", 10, &Plus::callback, this);
56  }
57 
58  void callback(const std_msgs::Float64::ConstPtr& input)
59  {
60  std_msgs::Float64Ptr output(new std_msgs::Float64());
61  output->data = input->data + value_;
62  NODELET_DEBUG("Adding %f to get %f", value_, output->data);
63  pub.publish(output);
64  }
65 
68  double value_;
69 };
70 
72 }
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void callback(const std_msgs::Float64::ConstPtr &input)
Definition: plus.cpp:58
virtual void onInit()
Definition: plus.cpp:50
ros::NodeHandle & getPrivateNodeHandle() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::Publisher pub
Definition: plus.cpp:66
bool getParam(const std::string &key, std::string &s) const
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
#define NODELET_DEBUG(...)
ros::Subscriber sub
Definition: plus.cpp:67


nodelet_tutorial_math
Author(s): Tully Foote
autogenerated on Sat Apr 4 2020 03:47:17