#include <gazebo_ros_power_monitor.h>
Public Member Functions | |
| GazeboRosPowerMonitor () | |
| virtual | ~GazeboRosPowerMonitor () |
Protected Member Functions | |
| virtual void | InitChild () |
| void | Load (physics::ModelPtr _parent, sdf::ElementPtr _sdf) |
| virtual void | UpdateChild () |
Private Member Functions | |
| void | SetPlug (const pr2_gazebo_plugins::PlugCommandConstPtr &plug_msg) |
| listen to ROS to see if we are charging | |
Private Attributes | |
| double | charge_ |
| charge state (Ah) | |
| double | charge_rate_ |
| charge rate (W) | |
| double | charge_voltage_ |
| charge voltage when plugged in (V) | |
| double | curr_time_ |
| double | discharge_rate_ |
| charge rate when plugged in (W) | |
| double | discharge_voltage_ |
| discharge voltage when plugged in (V) | |
| double | full_capacity_ |
| internal variables for keeping track of simulated battery | |
| double | last_time_ |
| boost::mutex | lock_ |
| lock access to fields that are used in message callbacks | |
| transport::NodePtr | node |
| gazebo::physics::ModelPtr | parent_model_ |
| ros::Subscriber | plugged_in_sub_ |
| pr2_msgs::PowerState | power_state_ |
| ros::Publisher | power_state_pub_ |
| double | power_state_rate_ |
| rate to broadcast power state message | |
| std::string | power_state_topic_ |
| std::string | robot_namespace_ |
| ros::NodeHandle * | rosnode_ |
| common::Time | simTime |
| transport::SubscriberPtr | statsSub |
| event::ConnectionPtr | updateConnection |
| double | voltage_ |
| voltage (V) | |
| physics::WorldPtr | world |
Definition at line 49 of file gazebo_ros_power_monitor.h.
Definition at line 45 of file gazebo_ros_power_monitor.cpp.
| gazebo::GazeboRosPowerMonitor::~GazeboRosPowerMonitor | ( | ) | [virtual] |
Definition at line 64 of file gazebo_ros_power_monitor.cpp.
| void gazebo::GazeboRosPowerMonitor::InitChild | ( | ) | [protected, virtual] |
Definition at line 126 of file gazebo_ros_power_monitor.cpp.
| void gazebo::GazeboRosPowerMonitor::Load | ( | physics::ModelPtr | _parent, |
| sdf::ElementPtr | _sdf | ||
| ) | [protected] |
Definition at line 81 of file gazebo_ros_power_monitor.cpp.
| void gazebo::GazeboRosPowerMonitor::SetPlug | ( | const pr2_gazebo_plugins::PlugCommandConstPtr & | plug_msg | ) | [private] |
listen to ROS to see if we are charging
Definition at line 179 of file gazebo_ros_power_monitor.cpp.
| void gazebo::GazeboRosPowerMonitor::UpdateChild | ( | ) | [protected, virtual] |
Definition at line 136 of file gazebo_ros_power_monitor.cpp.
double gazebo::GazeboRosPowerMonitor::charge_ [private] |
charge state (Ah)
Definition at line 110 of file gazebo_ros_power_monitor.h.
double gazebo::GazeboRosPowerMonitor::charge_rate_ [private] |
charge rate (W)
Definition at line 113 of file gazebo_ros_power_monitor.h.
double gazebo::GazeboRosPowerMonitor::charge_voltage_ [private] |
charge voltage when plugged in (V)
Definition at line 103 of file gazebo_ros_power_monitor.h.
double gazebo::GazeboRosPowerMonitor::curr_time_ [private] |
Definition at line 67 of file gazebo_ros_power_monitor.h.
double gazebo::GazeboRosPowerMonitor::discharge_rate_ [private] |
charge rate when plugged in (W)
discharge rate when not plugged in (W)
Definition at line 99 of file gazebo_ros_power_monitor.h.
double gazebo::GazeboRosPowerMonitor::discharge_voltage_ [private] |
discharge voltage when plugged in (V)
Definition at line 107 of file gazebo_ros_power_monitor.h.
double gazebo::GazeboRosPowerMonitor::full_capacity_ [private] |
internal variables for keeping track of simulated battery
full capacity of battery (Ah)
Definition at line 92 of file gazebo_ros_power_monitor.h.
double gazebo::GazeboRosPowerMonitor::last_time_ [private] |
Definition at line 68 of file gazebo_ros_power_monitor.h.
boost::mutex gazebo::GazeboRosPowerMonitor::lock_ [private] |
lock access to fields that are used in message callbacks
Definition at line 80 of file gazebo_ros_power_monitor.h.
transport::NodePtr gazebo::GazeboRosPowerMonitor::node [private] |
Definition at line 125 of file gazebo_ros_power_monitor.h.
gazebo::physics::ModelPtr gazebo::GazeboRosPowerMonitor::parent_model_ [private] |
Definition at line 66 of file gazebo_ros_power_monitor.h.
Definition at line 76 of file gazebo_ros_power_monitor.h.
Definition at line 82 of file gazebo_ros_power_monitor.h.
Definition at line 77 of file gazebo_ros_power_monitor.h.
double gazebo::GazeboRosPowerMonitor::power_state_rate_ [private] |
rate to broadcast power state message
Definition at line 86 of file gazebo_ros_power_monitor.h.
std::string gazebo::GazeboRosPowerMonitor::power_state_topic_ [private] |
Definition at line 73 of file gazebo_ros_power_monitor.h.
std::string gazebo::GazeboRosPowerMonitor::robot_namespace_ [private] |
Definition at line 72 of file gazebo_ros_power_monitor.h.
Definition at line 75 of file gazebo_ros_power_monitor.h.
common::Time gazebo::GazeboRosPowerMonitor::simTime [private] |
Definition at line 127 of file gazebo_ros_power_monitor.h.
transport::SubscriberPtr gazebo::GazeboRosPowerMonitor::statsSub [private] |
Definition at line 126 of file gazebo_ros_power_monitor.h.
Definition at line 122 of file gazebo_ros_power_monitor.h.
double gazebo::GazeboRosPowerMonitor::voltage_ [private] |
voltage (V)
Definition at line 116 of file gazebo_ros_power_monitor.h.
physics::WorldPtr gazebo::GazeboRosPowerMonitor::world [private] |
Definition at line 119 of file gazebo_ros_power_monitor.h.