Public Member Functions | Private Attributes | Static Private Attributes
shadowrobot::SRDiagnosticer Class Reference

#include <sr_diagnosticer.h>

List of all members.

Public Member Functions

void publish ()
 SRDiagnosticer (boost::shared_ptr< SRArticulatedRobot > sr_art_robot, hardware_types hw_type)
 ~SRDiagnosticer ()
 Destructor.

Private Attributes

hardware_types hardware_type
 store the hardware_type for this diagnosticer.
NodeHandle n_tilde
NodeHandle node
 ros node handle
Rate publish_rate
 the rate at which the data will be published. This can be set by a parameter in the launch file.
boost::shared_ptr
< SRArticulatedRobot
sr_articulated_robot
 The shadowhand object (can be either an object connected to the real robot or a virtual hand).
Publisher sr_diagnostics_pub
 The publisher which publishes the data to the \/diagnostics topic.

Static Private Attributes

static const double palm_msg_rate_const = 4000.0
 const to convert the rate data to Hz
static const double palm_numb_msg_const = 9.0
 const to convert the rate data to Hz

Detailed Description

Definition at line 60 of file sr_diagnosticer.h.


Constructor & Destructor Documentation

shadowrobot::SRDiagnosticer::SRDiagnosticer ( boost::shared_ptr< SRArticulatedRobot sr_art_robot,
hardware_types  hw_type 
)

Constructor initializing the ROS node, and setting the topic to which it publishes. The frequency at which this node will publish data is set by a parameter, read from ROS parameter server.

Parameters:
sr_art_robotA SRArticulatedRobot object, where the information to be published comes from.
hw_typeThe type of hardware we are publishing diagnostics about.

Definition at line 61 of file sr_diagnosticer.cpp.

Destructor.

Definition at line 77 of file sr_diagnosticer.cpp.


Member Function Documentation

The callback method which is called at a given frequency. Gets the data from the shadowhand / shadowarm object.

Definition at line 86 of file sr_diagnosticer.cpp.


Member Data Documentation

store the hardware_type for this diagnosticer.

Definition at line 98 of file sr_diagnosticer.h.

Definition at line 90 of file sr_diagnosticer.h.

ros node handle

Definition at line 90 of file sr_diagnosticer.h.

const double shadowrobot::SRDiagnosticer::palm_msg_rate_const = 4000.0 [static, private]

const to convert the rate data to Hz

Definition at line 84 of file sr_diagnosticer.h.

const double shadowrobot::SRDiagnosticer::palm_numb_msg_const = 9.0 [static, private]

const to convert the rate data to Hz

Definition at line 82 of file sr_diagnosticer.h.

the rate at which the data will be published. This can be set by a parameter in the launch file.

Definition at line 92 of file sr_diagnosticer.h.

The shadowhand object (can be either an object connected to the real robot or a virtual hand).

Definition at line 87 of file sr_diagnosticer.h.

The publisher which publishes the data to the \/diagnostics topic.

Definition at line 95 of file sr_diagnosticer.h.


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


sr_hand
Author(s): Ugo Cupcic
autogenerated on Fri Aug 28 2015 13:08:52