$search
power_monitor simulation More...
#include <gazebo_ros_power_monitor.h>
| Public Member Functions | |
| GazeboRosPowerMonitor (Entity *parent) | |
| virtual | ~GazeboRosPowerMonitor () | 
| Protected Member Functions | |
| virtual void | FiniChild () | 
| virtual void | InitChild () | 
| virtual void | LoadChild (XMLConfigNode *node) | 
| 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) | |
| ParamT< double > * | charge_rate_param_ | 
| charge rate when plugged in (W) | |
| ParamT< double > * | charge_voltage_param_ | 
| charge voltage when plugged in (V) | |
| double | curr_time_ | 
| ParamT< double > * | discharge_rate_param_ | 
| discharge rate when not plugged in (W) | |
| ParamT< double > * | discharge_voltage_param_ | 
| discharge voltage when plugged in (V) | |
| ParamT< double > * | full_capacity_param_ | 
| internal variables for keeping track of simulated battery | |
| double | last_time_ | 
| boost::mutex | lock_ | 
| lock access to fields that are used in message callbacks | |
| Model * | model_ | 
| ros::Subscriber | plugged_in_sub_ | 
| pr2_msgs::PowerState | power_state_ | 
| ros::Publisher | power_state_pub_ | 
| ParamT< double > * | power_state_rate_param_ | 
| rate to broadcast power state message | |
| ParamT< std::string > * | power_state_topic_param_ | 
| ParamT< std::string > * | robot_namespace_param_ | 
| ros::NodeHandle * | rosnode_ | 
| double | voltage_ | 
| voltage (V) | |
power_monitor simulation
    <!-- GazeboRosPowerMonitor -->
    <controller:gazebo_ros_power_monitor name="gazebo_ros_power_monitor_controller" plugin="libgazebo_ros_power_monitor.so">
        <alwaysOn>true</alwaysOn>
        <updateRate>1.0</updateRate>
        <timeout>5</timeout>
        <interface:audio name="power_monitor_dummy_interface" />
        <powerStateTopic>power_state</powerStateTopic>
        <powerStateRate>10.0</powerStateRate>
        <fullChargeCapacity>87.78</fullChargeCapacity>
        <dischargeRate>-474</dischargeRate>
        <chargeRate>525</chargeRate>
        <dischargeVoltage>15.52</dischargeVoltage>
        <chargeVoltage>16.41</chargeVoltage>
    </controller:gazebo_ros_power_monitor>
 Definition at line 101 of file gazebo_ros_power_monitor.h.
| gazebo::GazeboRosPowerMonitor::GazeboRosPowerMonitor | ( | Entity * | parent | ) | 
Definition at line 43 of file gazebo_ros_power_monitor.cpp.
| gazebo::GazeboRosPowerMonitor::~GazeboRosPowerMonitor | ( | ) |  [virtual] | 
Definition at line 62 of file gazebo_ros_power_monitor.cpp.
| void gazebo::GazeboRosPowerMonitor::FiniChild | ( | ) |  [protected, virtual] | 
Definition at line 161 of file gazebo_ros_power_monitor.cpp.
| void gazebo::GazeboRosPowerMonitor::InitChild | ( | ) |  [protected, virtual] | 
Definition at line 100 of file gazebo_ros_power_monitor.cpp.
| void gazebo::GazeboRosPowerMonitor::LoadChild | ( | XMLConfigNode * | node | ) |  [protected, virtual] | 
Definition at line 76 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 167 of file gazebo_ros_power_monitor.cpp.
| void gazebo::GazeboRosPowerMonitor::UpdateChild | ( | ) |  [protected, virtual] | 
Definition at line 114 of file gazebo_ros_power_monitor.cpp.
| double gazebo::GazeboRosPowerMonitor::charge_  [private] | 
charge state (Ah)
Definition at line 156 of file gazebo_ros_power_monitor.h.
| double gazebo::GazeboRosPowerMonitor::charge_rate_  [private] | 
charge rate (W)
Definition at line 159 of file gazebo_ros_power_monitor.h.
| ParamT<double>* gazebo::GazeboRosPowerMonitor::charge_rate_param_  [private] | 
charge rate when plugged in (W)
Definition at line 144 of file gazebo_ros_power_monitor.h.
| ParamT<double>* gazebo::GazeboRosPowerMonitor::charge_voltage_param_  [private] | 
charge voltage when plugged in (V)
Definition at line 150 of file gazebo_ros_power_monitor.h.
| double gazebo::GazeboRosPowerMonitor::curr_time_  [private] | 
Definition at line 120 of file gazebo_ros_power_monitor.h.
| ParamT<double>* gazebo::GazeboRosPowerMonitor::discharge_rate_param_  [private] | 
discharge rate when not plugged in (W)
Definition at line 147 of file gazebo_ros_power_monitor.h.
| ParamT<double>* gazebo::GazeboRosPowerMonitor::discharge_voltage_param_  [private] | 
discharge voltage when plugged in (V)
Definition at line 153 of file gazebo_ros_power_monitor.h.
| ParamT<double>* gazebo::GazeboRosPowerMonitor::full_capacity_param_  [private] | 
internal variables for keeping track of simulated battery
full capacity of battery (Ah)
Definition at line 141 of file gazebo_ros_power_monitor.h.
| double gazebo::GazeboRosPowerMonitor::last_time_  [private] | 
Definition at line 121 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 131 of file gazebo_ros_power_monitor.h.
| Model* gazebo::GazeboRosPowerMonitor::model_  [private] | 
Definition at line 119 of file gazebo_ros_power_monitor.h.
Definition at line 127 of file gazebo_ros_power_monitor.h.
Definition at line 133 of file gazebo_ros_power_monitor.h.
Definition at line 128 of file gazebo_ros_power_monitor.h.
| ParamT<double>* gazebo::GazeboRosPowerMonitor::power_state_rate_param_  [private] | 
rate to broadcast power state message
Definition at line 136 of file gazebo_ros_power_monitor.h.
| ParamT<std::string>* gazebo::GazeboRosPowerMonitor::power_state_topic_param_  [private] | 
Definition at line 124 of file gazebo_ros_power_monitor.h.
| ParamT<std::string>* gazebo::GazeboRosPowerMonitor::robot_namespace_param_  [private] | 
Definition at line 123 of file gazebo_ros_power_monitor.h.
Definition at line 126 of file gazebo_ros_power_monitor.h.
| double gazebo::GazeboRosPowerMonitor::voltage_  [private] | 
voltage (V)
Definition at line 162 of file gazebo_ros_power_monitor.h.