#include <gazebo_ros_power_monitor.h>
Public Member Functions | |
GazeboRosPowerMonitor () | |
virtual | ~GazeboRosPowerMonitor () |
Protected Member Functions | |
void | Load (physics::ModelPtr _parent, sdf::ElementPtr _sdf) |
virtual void | UpdateChild () |
Private Member Functions | |
virtual void | ConnectCb () |
virtual void | DisconnectCb () |
virtual void | LoadThread () |
virtual void | QueueThread () |
void | SetPlug (const pr2_gazebo_plugins::PlugCommandConstPtr &plug_msg) |
Private Attributes | |
boost::thread | callback_queue_thread_ |
double | charge_ |
charge state (Ah) More... | |
double | charge_rate_ |
charge rate (W) More... | |
double | charge_voltage_ |
charge voltage when plugged in (V) More... | |
int | connect_count_ |
boost::thread | deferred_load_thread_ |
double | discharge_rate_ |
discharge rate when not plugged in (W) More... | |
double | discharge_voltage_ |
discharge voltage when plugged in (V) More... | |
double | full_capacity_ |
full capacity of battery (Ah) More... | |
double | last_time_ |
latest time on callback is called More... | |
boost::mutex | lock_ |
lock access to fields that are used in message callbacks More... | |
ros::Subscriber | plugged_in_sub_ |
pr2_msgs::PowerState | power_state_ |
published messages More... | |
ros::Publisher | power_state_pub_ |
double | power_state_rate_ |
rate to broadcast power state message More... | |
std::string | power_state_topic_ |
name of published topic More... | |
ros::CallbackQueue | queue_ |
std::string | robot_namespace_ |
namespace of robot in ROS system More... | |
ros::NodeHandle * | rosnode_ |
sdf::ElementPtr | sdf_ |
event::ConnectionPtr | update_connection_ |
double | voltage_ |
voltage (V) More... | |
physics::WorldPtr | world_ |
Definition at line 51 of file gazebo_ros_power_monitor.h.
gazebo::GazeboRosPowerMonitor::GazeboRosPowerMonitor | ( | ) |
Definition at line 44 of file gazebo_ros_power_monitor.cpp.
|
virtual |
Definition at line 47 of file gazebo_ros_power_monitor.cpp.
|
privatevirtual |
Definition at line 170 of file gazebo_ros_power_monitor.cpp.
|
privatevirtual |
Definition at line 175 of file gazebo_ros_power_monitor.cpp.
|
protected |
Definition at line 57 of file gazebo_ros_power_monitor.cpp.
|
privatevirtual |
Definition at line 69 of file gazebo_ros_power_monitor.cpp.
|
privatevirtual |
Definition at line 180 of file gazebo_ros_power_monitor.cpp.
|
private |
Definition at line 247 of file gazebo_ros_power_monitor.cpp.
|
protectedvirtual |
Definition at line 189 of file gazebo_ros_power_monitor.cpp.
|
private |
Definition at line 93 of file gazebo_ros_power_monitor.h.
|
private |
charge state (Ah)
Definition at line 106 of file gazebo_ros_power_monitor.h.
|
private |
charge rate (W)
Definition at line 82 of file gazebo_ros_power_monitor.h.
|
private |
charge voltage when plugged in (V)
Definition at line 86 of file gazebo_ros_power_monitor.h.
|
private |
Definition at line 95 of file gazebo_ros_power_monitor.h.
|
private |
Definition at line 92 of file gazebo_ros_power_monitor.h.
|
private |
discharge rate when not plugged in (W)
Definition at line 80 of file gazebo_ros_power_monitor.h.
|
private |
discharge voltage when plugged in (V)
Definition at line 84 of file gazebo_ros_power_monitor.h.
|
private |
full capacity of battery (Ah)
Definition at line 78 of file gazebo_ros_power_monitor.h.
|
private |
latest time on callback is called
Definition at line 104 of file gazebo_ros_power_monitor.h.
|
private |
lock access to fields that are used in message callbacks
Definition at line 112 of file gazebo_ros_power_monitor.h.
|
private |
Definition at line 91 of file gazebo_ros_power_monitor.h.
|
private |
published messages
Definition at line 110 of file gazebo_ros_power_monitor.h.
|
private |
Definition at line 90 of file gazebo_ros_power_monitor.h.
|
private |
rate to broadcast power state message
Definition at line 76 of file gazebo_ros_power_monitor.h.
|
private |
name of published topic
Definition at line 74 of file gazebo_ros_power_monitor.h.
|
private |
Definition at line 94 of file gazebo_ros_power_monitor.h.
|
private |
namespace of robot in ROS system
Definition at line 72 of file gazebo_ros_power_monitor.h.
|
private |
Definition at line 89 of file gazebo_ros_power_monitor.h.
|
private |
Definition at line 100 of file gazebo_ros_power_monitor.h.
|
private |
Definition at line 98 of file gazebo_ros_power_monitor.h.
|
private |
voltage (V)
Definition at line 108 of file gazebo_ros_power_monitor.h.
|
private |
Definition at line 99 of file gazebo_ros_power_monitor.h.