30 #ifndef PR2_GAZEBO_PLUGINS_ROS_POWER_MONITOR_H 31 #define PR2_GAZEBO_PLUGINS_ROS_POWER_MONITOR_H 35 #include <boost/thread/mutex.hpp> 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> 46 #include <pr2_msgs/PowerState.h> 47 #include <pr2_gazebo_plugins/PlugCommand.h> 59 void Load( physics::ModelPtr _parent, sdf::ElementPtr _sdf );
67 void SetPlug(
const pr2_gazebo_plugins::PlugCommandConstPtr& plug_msg);
ros::Publisher power_state_pub_
ros::NodeHandle * rosnode_
event::ConnectionPtr update_connection_
double discharge_rate_
discharge rate when not plugged in (W)
std::string robot_namespace_
namespace of robot in ROS system
virtual ~GazeboRosPowerMonitor()
virtual void DisconnectCb()
virtual void UpdateChild()
double charge_
charge state (Ah)
boost::thread deferred_load_thread_
void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
double last_time_
latest time on callback is called
pr2_msgs::PowerState power_state_
published messages
double voltage_
voltage (V)
void SetPlug(const pr2_gazebo_plugins::PlugCommandConstPtr &plug_msg)
ros::CallbackQueue queue_
virtual void LoadThread()
double charge_rate_
charge rate (W)
double charge_voltage_
charge voltage when plugged in (V)
virtual void QueueThread()
double full_capacity_
full capacity of battery (Ah)
boost::thread callback_queue_thread_
ros::Subscriber plugged_in_sub_
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