Public Member Functions | Private Attributes
control_toolbox::PidGainsSetter Class Reference

Sets up services for quickly changing the gains for a control_toolbox::Pid Pid object. More...

#include <pid_gains_setter.h>

List of all members.

Public Member Functions

PidGainsSetteradd (Pid *pid)
 Adds a Pid object.
void advertise (const ros::NodeHandle &n)
 Advertises the "set_gains" service, initializing the PidGainsSetter.
void advertise (const std::string &ns)
 Advertises the "set_gains" service, initializing the PidGainsSetter.
 PidGainsSetter ()
bool setGains (control_toolbox::SetPidGains::Request &req, control_toolbox::SetPidGains::Response &resp)
 ~PidGainsSetter ()

Private Attributes

ros::NodeHandle node_
std::vector< Pid * > pids_
ros::ServiceServer serve_set_gains_

Detailed Description

Sets up services for quickly changing the gains for a control_toolbox::Pid Pid object.

The PidGainsSetter class provides services for changing the gains of Pid objects over ROS. It advertise the "set_gains" service in the NodeHandle's namespace, with a type of control_toolbox/SetPidGains.

To use the object, add pids to the gains setter and then call advertise(). The PidGainsSetter will then update the gains of all the Pid objects when you call the set_gains service. (If you wish to have Pids with different gains, then you should use multiple PidGainsSetter objects).

 ros::NodeHandle node;
 control_toolbox::Pid a, b, c;
 control_toolbox::PidGainsSetter pid_gains_setter;

 pid_gains_setter.add(&a);
 pid_gains_setter.add(&b).add(&c);
 pid_gains_setter.advertise(node);
 

ROS API

Definition at line 74 of file pid_gains_setter.h.


Constructor & Destructor Documentation

Definition at line 77 of file pid_gains_setter.h.

Definition at line 34 of file pid_gains_setter.cpp.


Member Function Documentation

Adds a Pid object.

Adds a Pid object to be modified when new gains are set over the service.

Definition at line 39 of file pid_gains_setter.cpp.

Advertises the "set_gains" service, initializing the PidGainsSetter.

Definition at line 46 of file pid_gains_setter.cpp.

void control_toolbox::PidGainsSetter::advertise ( const std::string &  ns) [inline]

Advertises the "set_gains" service, initializing the PidGainsSetter.

Definition at line 95 of file pid_gains_setter.h.

bool control_toolbox::PidGainsSetter::setGains ( control_toolbox::SetPidGains::Request &  req,
control_toolbox::SetPidGains::Response &  resp 
)

Definition at line 52 of file pid_gains_setter.cpp.


Member Data Documentation

Definition at line 101 of file pid_gains_setter.h.

Definition at line 103 of file pid_gains_setter.h.

Definition at line 102 of file pid_gains_setter.h.


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


control_toolbox
Author(s): Melonee Wise, Sachin Chitta, John Hsu
autogenerated on Fri Apr 15 2016 15:39:29