gazebo_ros_power_monitor.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, 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 
30 #ifndef PR2_GAZEBO_PLUGINS_ROS_POWER_MONITOR_H
31 #define PR2_GAZEBO_PLUGINS_ROS_POWER_MONITOR_H
32 
33 #include <map>
34 #include <vector>
35 #include <boost/thread/mutex.hpp>
36 
37 #include <gazebo/physics/World.hh>
38 #include <gazebo/physics/Model.hh>
39 #include <gazebo/physics/physics.hh>
40 #include <gazebo/common/Time.hh>
41 #include <gazebo/common/Plugin.hh>
42 
43 #include <ros/ros.h>
44 #include <ros/advertise_options.h>
45 #include <ros/callback_queue.h>
46 #include <pr2_msgs/PowerState.h>
47 #include <pr2_gazebo_plugins/PlugCommand.h>
48 
49 namespace gazebo {
50 
51 class GazeboRosPowerMonitor : public ModelPlugin
52 {
53 public:
55  virtual ~GazeboRosPowerMonitor();
56 
57 protected:
58  // Inherited from Controller
59  void Load( physics::ModelPtr _parent, sdf::ElementPtr _sdf );
60  virtual void UpdateChild();
61 
62 private:
63  virtual void LoadThread();
64  virtual void ConnectCb();
65  virtual void DisconnectCb();
66  virtual void QueueThread();
67  void SetPlug(const pr2_gazebo_plugins::PlugCommandConstPtr& plug_msg);
68 
69 private:
70  // parameters
72  std::string robot_namespace_;
74  std::string power_state_topic_;
82  double charge_rate_;
87 
88  // ros
92  boost::thread deferred_load_thread_;
93  boost::thread callback_queue_thread_;
96 
97  // gazebo
98  event::ConnectionPtr update_connection_;
99  physics::WorldPtr world_;
100  sdf::ElementPtr sdf_;
101 
102  // internal variables
104  double last_time_;
106  double charge_;
108  double voltage_;
110  pr2_msgs::PowerState power_state_;
112  boost::mutex lock_;
113 };
114 
115 }
116 
117 #endif
double discharge_rate_
discharge rate when not plugged in (W)
std::string robot_namespace_
namespace of robot in ROS system
void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
double last_time_
latest time on callback is called
pr2_msgs::PowerState power_state_
published messages
void SetPlug(const pr2_gazebo_plugins::PlugCommandConstPtr &plug_msg)
double charge_voltage_
charge voltage when plugged in (V)
double full_capacity_
full capacity of battery (Ah)
double power_state_rate_
rate to broadcast power state message
double discharge_voltage_
discharge voltage when plugged in (V)
boost::mutex lock_
lock access to fields that are used in message callbacks
std::string power_state_topic_
name of published topic


pr2_gazebo_plugins
Author(s): John Hsu
autogenerated on Fri May 3 2019 02:24:24