#include <motor_param.h>
Public Member Functions | |
int | getOperativeMode () |
void | initConfigurator (bool load_from_board) |
initConfigurator Initialize all parameter and syncronize parameters between ros and roboteq board More... | |
MotorParamConfigurator (const ros::NodeHandle &nh, roboteq::serial_controller *serial, std::string name, unsigned int number) | |
MotorParamConfigurator. More... | |
void | setOperativeMode (int type) |
setOperativeMode Reference in page 321 - MMOD More... | |
Private Member Functions | |
void | getParamFromRoboteq () |
getParamFromRoboteq Load parameters from Roboteq board More... | |
void | reconfigureCBParam (roboteq_control::RoboteqParameterConfig &config, uint32_t level) |
reconfigureCBParam when the dynamic reconfigurator change some values start this method More... | |
void | reconfigureCBPIDtype (roboteq_control::RoboteqPIDtypeConfig &config, uint32_t level) |
reconfigureCBEncoder when the dynamic reconfigurator change some values start this method More... | |
Private Attributes | |
roboteq_control::RoboteqParameterConfig | _last_param_config |
roboteq_control::RoboteqPIDtypeConfig | _last_pid_type_config |
roboteq_control::RoboteqParameterConfig | default_param_config |
roboteq_control::RoboteqPIDtypeConfig | default_pid_type_config |
dynamic_reconfigure::Server< roboteq_control::RoboteqParameterConfig > * | ds_param |
Dynamic reconfigure parameters. More... | |
dynamic_reconfigure::Server< roboteq_control::RoboteqPIDtypeConfig > * | ds_pid_type |
Dynamic reconfigure PID. More... | |
string | mName |
Associate name space. More... | |
unsigned int | mNumber |
Number motor. More... | |
roboteq::serial_controller * | mSerial |
Serial port. More... | |
ros::NodeHandle | nh_ |
Private namespace. More... | |
bool | setup_param |
Setup variable. More... | |
bool | setup_pid_type |
Copyright (C) 2017, Raffaello Bonghi raffa All rights reserved ello @rnex t.it
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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 43 of file motor_param.h.
MotorParamConfigurator::MotorParamConfigurator | ( | const ros::NodeHandle & | nh, |
roboteq::serial_controller * | serial, | ||
std::string | name, | ||
unsigned int | number | ||
) |
nh | |
serial | |
name | |
number | Copyright (C) 2017, Raffaello Bonghi raffa All rights reserved ello @rnex t.it |
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
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_param.cpp.
int MotorParamConfigurator::getOperativeMode | ( | ) |
Definition at line 88 of file motor_param.cpp.
|
private |
getParamFromRoboteq Load parameters from Roboteq board
Definition at line 121 of file motor_param.cpp.
void MotorParamConfigurator::initConfigurator | ( | bool | load_from_board | ) |
initConfigurator Initialize all parameter and syncronize parameters between ros and roboteq board
load_from_board | If true load all paramter from roboteq board |
Definition at line 45 of file motor_param.cpp.
|
private |
reconfigureCBParam when the dynamic reconfigurator change some values start this method
config | variable with all configuration from dynamic reconfigurator |
level |
Definition at line 197 of file motor_param.cpp.
|
private |
reconfigureCBEncoder when the dynamic reconfigurator change some values start this method
config | variable with all configuration from dynamic reconfigurator |
level |
Definition at line 100 of file motor_param.cpp.
void MotorParamConfigurator::setOperativeMode | ( | int | type | ) |
setOperativeMode Reference in page 321 - MMOD
type | The operating_mode 0 - open_loop 1 - closed_loop_speed 2 - closed_loop_position_relative 3 - closed_loop_count_position 4 - closed_loop_position_tracking 5 - torque 6 - closed_loop_speed_position |
Definition at line 82 of file motor_param.cpp.
|
private |
Definition at line 106 of file motor_param.h.
|
private |
Definition at line 107 of file motor_param.h.
|
private |
Definition at line 106 of file motor_param.h.
|
private |
Definition at line 107 of file motor_param.h.
|
private |
Dynamic reconfigure parameters.
Definition at line 88 of file motor_param.h.
|
private |
Dynamic reconfigure PID.
Definition at line 97 of file motor_param.h.
|
private |
Associate name space.
Definition at line 79 of file motor_param.h.
|
private |
Number motor.
Definition at line 81 of file motor_param.h.
|
private |
Serial port.
Definition at line 85 of file motor_param.h.
|
private |
Private namespace.
Definition at line 83 of file motor_param.h.
|
private |
Setup variable.
Definition at line 76 of file motor_param.h.
|
private |
Definition at line 76 of file motor_param.h.