Public Member Functions | Private Member Functions | Private Attributes | List of all members
MotorPIDConfigurator Class Reference

#include <motor_pid.h>

Public Member Functions

void initConfigurator (bool load_from_board)
 
 MotorPIDConfigurator (const ros::NodeHandle &nh, roboteq::serial_controller *serial, string path, string name, unsigned int number)
 MotorPIDConfigurator Initialize the dynamic reconfigurator. More...
 
void setPIDconfiguration ()
 

Private Member Functions

void getPIDFromRoboteq ()
 getPIDFromRoboteq Load PID parameters from Roboteq board More...
 
void reconfigureCBPID (roboteq_control::RoboteqPIDConfig &config, uint32_t level)
 reconfigureCBEncoder when the dynamic reconfigurator change some values start this method More...
 

Private Attributes

roboteq_control::RoboteqPIDConfig _last_pid_config
 
roboteq_control::RoboteqPIDConfig default_pid_config
 
dynamic_reconfigure::Server< roboteq_control::RoboteqPIDConfig > * ds_pid
 Dynamic reconfigure PID. More...
 
string mName
 Associate name space. More...
 
unsigned int mNumber
 Number motor. More...
 
roboteq::serial_controllermSerial
 Serial port. More...
 
string mType
 
ros::NodeHandle nh_
 Private namespace. More...
 
bool setup_pid
 Setup variable. More...
 

Detailed Description

Definition at line 41 of file motor_pid.h.

Constructor & Destructor Documentation

MotorPIDConfigurator::MotorPIDConfigurator ( const ros::NodeHandle nh,
roboteq::serial_controller serial,
string  path,
string  name,
unsigned int  number 
)

MotorPIDConfigurator Initialize the dynamic reconfigurator.

Parameters
nhNodehandle of the system
serialserial port
pathoriginal path to start to find all rosparam variable
namename of the PID configuration
numbernumber of motor

Copyright (C) 2017, Raffaello Bonghi raffa.nosp@m.ello.nosp@m.@rnex.nosp@m.t.it All rights reserved

Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:

  1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer.
  2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution.
  3. Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission.

THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.

Definition at line 33 of file motor_pid.cpp.

Member Function Documentation

void MotorPIDConfigurator::getPIDFromRoboteq ( )
private

getPIDFromRoboteq Load PID parameters from Roboteq board

Definition at line 63 of file motor_pid.cpp.

void MotorPIDConfigurator::initConfigurator ( bool  load_from_board)

Definition at line 48 of file motor_pid.cpp.

void MotorPIDConfigurator::reconfigureCBPID ( roboteq_control::RoboteqPIDConfig &  config,
uint32_t  level 
)
private

reconfigureCBEncoder when the dynamic reconfigurator change some values start this method

Parameters
configvariable with all configuration from dynamic reconfigurator
level

Definition at line 172 of file motor_pid.cpp.

void MotorPIDConfigurator::setPIDconfiguration ( )

Definition at line 120 of file motor_pid.cpp.

Member Data Documentation

roboteq_control::RoboteqPIDConfig MotorPIDConfigurator::_last_pid_config
private

Definition at line 82 of file motor_pid.h.

roboteq_control::RoboteqPIDConfig MotorPIDConfigurator::default_pid_config
private

Definition at line 82 of file motor_pid.h.

dynamic_reconfigure::Server<roboteq_control::RoboteqPIDConfig>* MotorPIDConfigurator::ds_pid
private

Dynamic reconfigure PID.

Definition at line 73 of file motor_pid.h.

string MotorPIDConfigurator::mName
private

Associate name space.

Definition at line 63 of file motor_pid.h.

unsigned int MotorPIDConfigurator::mNumber
private

Number motor.

Definition at line 66 of file motor_pid.h.

roboteq::serial_controller* MotorPIDConfigurator::mSerial
private

Serial port.

Definition at line 70 of file motor_pid.h.

string MotorPIDConfigurator::mType
private

Definition at line 64 of file motor_pid.h.

ros::NodeHandle MotorPIDConfigurator::nh_
private

Private namespace.

Definition at line 68 of file motor_pid.h.

bool MotorPIDConfigurator::setup_pid
private

Setup variable.

Definition at line 60 of file motor_pid.h.


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


roboteq_control
Author(s): Raffaello Bonghi
autogenerated on Wed Jan 3 2018 03:48:23