Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes | List of all members
gazebo::GazeboRosPowerMonitor Class Reference

#include <gazebo_ros_power_monitor.h>

Inheritance diagram for gazebo::GazeboRosPowerMonitor:
Inheritance graph
[legend]

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::NodeHandlerosnode_
 
sdf::ElementPtr sdf_
 
event::ConnectionPtr update_connection_
 
double voltage_
 voltage (V) More...
 
physics::WorldPtr world_
 

Detailed Description

Definition at line 51 of file gazebo_ros_power_monitor.h.

Constructor & Destructor Documentation

gazebo::GazeboRosPowerMonitor::GazeboRosPowerMonitor ( )

Definition at line 44 of file gazebo_ros_power_monitor.cpp.

gazebo::GazeboRosPowerMonitor::~GazeboRosPowerMonitor ( )
virtual

Definition at line 47 of file gazebo_ros_power_monitor.cpp.

Member Function Documentation

void gazebo::GazeboRosPowerMonitor::ConnectCb ( )
privatevirtual

Definition at line 170 of file gazebo_ros_power_monitor.cpp.

void gazebo::GazeboRosPowerMonitor::DisconnectCb ( )
privatevirtual

Definition at line 175 of file gazebo_ros_power_monitor.cpp.

void gazebo::GazeboRosPowerMonitor::Load ( physics::ModelPtr  _parent,
sdf::ElementPtr  _sdf 
)
protected

Definition at line 57 of file gazebo_ros_power_monitor.cpp.

void gazebo::GazeboRosPowerMonitor::LoadThread ( )
privatevirtual

Definition at line 69 of file gazebo_ros_power_monitor.cpp.

void gazebo::GazeboRosPowerMonitor::QueueThread ( )
privatevirtual

Definition at line 180 of file gazebo_ros_power_monitor.cpp.

void gazebo::GazeboRosPowerMonitor::SetPlug ( const pr2_gazebo_plugins::PlugCommandConstPtr &  plug_msg)
private

Definition at line 247 of file gazebo_ros_power_monitor.cpp.

void gazebo::GazeboRosPowerMonitor::UpdateChild ( )
protectedvirtual

Definition at line 189 of file gazebo_ros_power_monitor.cpp.

Member Data Documentation

boost::thread gazebo::GazeboRosPowerMonitor::callback_queue_thread_
private

Definition at line 93 of file gazebo_ros_power_monitor.h.

double gazebo::GazeboRosPowerMonitor::charge_
private

charge state (Ah)

Definition at line 106 of file gazebo_ros_power_monitor.h.

double gazebo::GazeboRosPowerMonitor::charge_rate_
private

charge rate (W)

Definition at line 82 of file gazebo_ros_power_monitor.h.

double gazebo::GazeboRosPowerMonitor::charge_voltage_
private

charge voltage when plugged in (V)

Definition at line 86 of file gazebo_ros_power_monitor.h.

int gazebo::GazeboRosPowerMonitor::connect_count_
private

Definition at line 95 of file gazebo_ros_power_monitor.h.

boost::thread gazebo::GazeboRosPowerMonitor::deferred_load_thread_
private

Definition at line 92 of file gazebo_ros_power_monitor.h.

double gazebo::GazeboRosPowerMonitor::discharge_rate_
private

discharge rate when not plugged in (W)

Definition at line 80 of file gazebo_ros_power_monitor.h.

double gazebo::GazeboRosPowerMonitor::discharge_voltage_
private

discharge voltage when plugged in (V)

Definition at line 84 of file gazebo_ros_power_monitor.h.

double gazebo::GazeboRosPowerMonitor::full_capacity_
private

full capacity of battery (Ah)

Definition at line 78 of file gazebo_ros_power_monitor.h.

double gazebo::GazeboRosPowerMonitor::last_time_
private

latest time on callback is called

Definition at line 104 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 112 of file gazebo_ros_power_monitor.h.

ros::Subscriber gazebo::GazeboRosPowerMonitor::plugged_in_sub_
private

Definition at line 91 of file gazebo_ros_power_monitor.h.

pr2_msgs::PowerState gazebo::GazeboRosPowerMonitor::power_state_
private

published messages

Definition at line 110 of file gazebo_ros_power_monitor.h.

ros::Publisher gazebo::GazeboRosPowerMonitor::power_state_pub_
private

Definition at line 90 of file gazebo_ros_power_monitor.h.

double gazebo::GazeboRosPowerMonitor::power_state_rate_
private

rate to broadcast power state message

Definition at line 76 of file gazebo_ros_power_monitor.h.

std::string gazebo::GazeboRosPowerMonitor::power_state_topic_
private

name of published topic

Definition at line 74 of file gazebo_ros_power_monitor.h.

ros::CallbackQueue gazebo::GazeboRosPowerMonitor::queue_
private

Definition at line 94 of file gazebo_ros_power_monitor.h.

std::string gazebo::GazeboRosPowerMonitor::robot_namespace_
private

namespace of robot in ROS system

Definition at line 72 of file gazebo_ros_power_monitor.h.

ros::NodeHandle* gazebo::GazeboRosPowerMonitor::rosnode_
private

Definition at line 89 of file gazebo_ros_power_monitor.h.

sdf::ElementPtr gazebo::GazeboRosPowerMonitor::sdf_
private

Definition at line 100 of file gazebo_ros_power_monitor.h.

event::ConnectionPtr gazebo::GazeboRosPowerMonitor::update_connection_
private

Definition at line 98 of file gazebo_ros_power_monitor.h.

double gazebo::GazeboRosPowerMonitor::voltage_
private

voltage (V)

Definition at line 108 of file gazebo_ros_power_monitor.h.

physics::WorldPtr gazebo::GazeboRosPowerMonitor::world_
private

Definition at line 99 of file gazebo_ros_power_monitor.h.


The documentation for this class was generated from the following files:


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