#include <md49_base_controller_class.h>
Public Member Functions | |
BaseController () | |
Constructor for class BaseController. | |
void | cmd_vel_callback (const geometry_msgs::Twist &vel_cmd) |
This is the callback-function for topic /cmd_vel. | |
void | disable_regulator (void) |
This function disables regulator on MD49. | |
void | disable_timeout (void) |
This function disables Timeout on MD49. | |
void | enable_regulator (void) |
This function enables regulator on MD49. | |
void | enable_timeout (void) |
This function enables timeout on MD49. | |
int | get_acceleration () |
This function reads the acceleration that is set from MD49. | |
int | get_actual_speed_l () |
get_actual_speed_l | |
int | get_actual_speed_r () |
get_actual_speed_r | |
int | get_current_l () |
This function reads left drives current from MD49. | |
int | get_current_r () |
This function reads right drives current from MD49. | |
void | get_encoders (void) |
This function reads encodervalues from MD49. | |
int | get_error () |
This function reads error code from MD49. | |
int | get_initial_md49_acceleration () |
get_initial_md49_acceleration | |
int | get_initial_md49_mode () |
get_initial_md49_mode | |
int | get_initial_md49_regulator () |
get_initial_md49_regulator | |
int | get_initial_md49_timeout () |
get_initial_md49_timeout | |
int | get_mode () |
This function reads the mode that is set from MD49. | |
int | get_requested_speed_l () |
get_requested_speed_l | |
int | get_requested_speed_r () |
get_requested_speed_r | |
int | get_speed_l () |
This function reads left drives speed from MD49. | |
int | get_speed_r () |
This function reads right drives speed from MD49. | |
int | get_volts () |
This function reads supply voltage from MD49. | |
void | init_md49 (int speed_l, int speed_r, int mode, int acceleration, bool timeout, bool regulator) |
This function sets parameters for MD49 as read from config file or as set as defaults. | |
void | open_serialport () |
This function opens serial port MD49 is connected to. | |
void | publish_encoders () |
This function reads encodervalues from MD49 and publishes them as topic /md49_encoders. | |
void | publish_md49_data () |
This function reads data and parameters from MD49 and publishes them as topic /md49_data. | |
void | reset_encoders (void) |
This function resets encoders on MD49. | |
void | set_acceleration (int acceleration) |
This function sets acceleration on MD49. | |
void | set_actual_speed_l (int speed_l) |
set_actual_speed_l | |
void | set_actual_speed_r (int speed_r) |
set_actual_speed_r | |
void | set_mode (int mode) |
This function sets mode on MD49. | |
void | set_requested_speed_l (int speed_l) |
set_requested_speed_l | |
void | set_requested_speed_r (int speed_r) |
set_requested_speed_r | |
void | set_speed (int speed_l, int speed_r) |
This function sets speed for left and right drive on MD49. | |
Public Attributes | |
ros::NodeHandle | n |
Private Attributes | |
int | actual_speed_l |
int | actual_speed_r |
cereal::CerealPort | device |
int | initial_md49_acceleration |
int | initial_md49_mode |
bool | initial_md49_regulator |
bool | initial_md49_timeout |
md49_messages::md49_data | md49_data |
ros::Publisher | md49_data_pub |
md49_messages::md49_encoders | md49_encoders |
ros::Publisher | md49_encoders_pub |
char | reply [8] |
int | requested_speed_l |
int | requested_speed_r |
std::string | serialport |
int | serialport_bps |
ros::Subscriber | sub_cmd_vel |
Definition at line 6 of file md49_base_controller_class.h.
BaseController::BaseController | ( | ) | [inline] |
Constructor for class BaseController.
Definition at line 15 of file md49_base_controller_class.h.
void BaseController::cmd_vel_callback | ( | const geometry_msgs::Twist & | vel_cmd | ) | [inline] |
This is the callback-function for topic /cmd_vel.
vel_cmd |
Definition at line 39 of file md49_base_controller_class.h.
void BaseController::disable_regulator | ( | void | ) | [inline] |
This function disables regulator on MD49.
Definition at line 193 of file md49_base_controller_class.h.
void BaseController::disable_timeout | ( | void | ) | [inline] |
This function disables Timeout on MD49.
Definition at line 184 of file md49_base_controller_class.h.
void BaseController::enable_regulator | ( | void | ) | [inline] |
This function enables regulator on MD49.
Definition at line 175 of file md49_base_controller_class.h.
void BaseController::enable_timeout | ( | void | ) | [inline] |
This function enables timeout on MD49.
Definition at line 166 of file md49_base_controller_class.h.
int BaseController::get_acceleration | ( | ) | [inline] |
This function reads the acceleration that is set from MD49.
Definition at line 203 of file md49_base_controller_class.h.
int BaseController::get_actual_speed_l | ( | ) | [inline] |
int BaseController::get_actual_speed_r | ( | ) | [inline] |
int BaseController::get_current_l | ( | ) | [inline] |
This function reads left drives current from MD49.
Definition at line 307 of file md49_base_controller_class.h.
int BaseController::get_current_r | ( | ) | [inline] |
This function reads right drives current from MD49.
Definition at line 321 of file md49_base_controller_class.h.
void BaseController::get_encoders | ( | void | ) | [inline] |
This function reads encodervalues from MD49.
Definition at line 258 of file md49_base_controller_class.h.
int BaseController::get_error | ( | ) | [inline] |
This function reads error code from MD49.
Definition at line 335 of file md49_base_controller_class.h.
int BaseController::get_initial_md49_acceleration | ( | ) | [inline] |
int BaseController::get_initial_md49_mode | ( | ) | [inline] |
int BaseController::get_initial_md49_regulator | ( | ) | [inline] |
int BaseController::get_initial_md49_timeout | ( | ) | [inline] |
int BaseController::get_mode | ( | ) | [inline] |
This function reads the mode that is set from MD49.
Definition at line 217 of file md49_base_controller_class.h.
int BaseController::get_requested_speed_l | ( | ) | [inline] |
int BaseController::get_requested_speed_r | ( | ) | [inline] |
int BaseController::get_speed_l | ( | ) | [inline] |
This function reads left drives speed from MD49.
Definition at line 231 of file md49_base_controller_class.h.
int BaseController::get_speed_r | ( | ) | [inline] |
This function reads right drives speed from MD49.
Definition at line 245 of file md49_base_controller_class.h.
int BaseController::get_volts | ( | ) | [inline] |
This function reads supply voltage from MD49.
Definition at line 293 of file md49_base_controller_class.h.
void BaseController::init_md49 | ( | int | speed_l, |
int | speed_r, | ||
int | mode, | ||
int | acceleration, | ||
bool | timeout, | ||
bool | regulator | ||
) | [inline] |
This function sets parameters for MD49 as read from config file or as set as defaults.
speed_l | |
speed_r | |
mode | |
acceleration | |
timeout | |
regulator |
Definition at line 106 of file md49_base_controller_class.h.
void BaseController::open_serialport | ( | ) | [inline] |
This function opens serial port MD49 is connected to.
Definition at line 62 of file md49_base_controller_class.h.
void BaseController::publish_encoders | ( | ) | [inline] |
This function reads encodervalues from MD49 and publishes them as topic /md49_encoders.
Definition at line 75 of file md49_base_controller_class.h.
void BaseController::publish_md49_data | ( | ) | [inline] |
This function reads data and parameters from MD49 and publishes them as topic /md49_data.
Definition at line 84 of file md49_base_controller_class.h.
void BaseController::reset_encoders | ( | void | ) | [inline] |
This function resets encoders on MD49.
Definition at line 349 of file md49_base_controller_class.h.
void BaseController::set_acceleration | ( | int | acceleration | ) | [inline] |
This function sets acceleration on MD49.
acceleration |
Definition at line 157 of file md49_base_controller_class.h.
void BaseController::set_actual_speed_l | ( | int | speed_l | ) | [inline] |
void BaseController::set_actual_speed_r | ( | int | speed_r | ) | [inline] |
void BaseController::set_mode | ( | int | mode | ) | [inline] |
This function sets mode on MD49.
mode |
Definition at line 147 of file md49_base_controller_class.h.
void BaseController::set_requested_speed_l | ( | int | speed_l | ) | [inline] |
set_requested_speed_l
speed_l |
Definition at line 375 of file md49_base_controller_class.h.
void BaseController::set_requested_speed_r | ( | int | speed_r | ) | [inline] |
set_requested_speed_r
speed_r |
Definition at line 383 of file md49_base_controller_class.h.
void BaseController::set_speed | ( | int | speed_l, |
int | speed_r | ||
) | [inline] |
This function sets speed for left and right drive on MD49.
speed_l | |
speed_r |
Definition at line 133 of file md49_base_controller_class.h.
int BaseController::actual_speed_l [private] |
Definition at line 456 of file md49_base_controller_class.h.
int BaseController::actual_speed_r [private] |
buffers actual set speed_l and speed_r
Definition at line 456 of file md49_base_controller_class.h.
cereal::CerealPort BaseController::device [private] |
serialport
Definition at line 453 of file md49_base_controller_class.h.
int BaseController::initial_md49_acceleration [private] |
MD49 Acceleration, is read from parameters server
Definition at line 458 of file md49_base_controller_class.h.
int BaseController::initial_md49_mode [private] |
MD49 Mode, is read from parameters server
Definition at line 457 of file md49_base_controller_class.h.
bool BaseController::initial_md49_regulator [private] |
MD40 Regulator-Mode , is read from parameters server
Definition at line 460 of file md49_base_controller_class.h.
bool BaseController::initial_md49_timeout [private] |
MD49 Timeout-Mode, is read from parameters server
Definition at line 459 of file md49_base_controller_class.h.
md49_messages::md49_data BaseController::md49_data [private] |
topic /md49_data
Definition at line 465 of file md49_base_controller_class.h.
ros::Publisher BaseController::md49_data_pub [private] |
Definition at line 468 of file md49_base_controller_class.h.
md49_messages::md49_encoders BaseController::md49_encoders [private] |
topic /md49_encoders
Definition at line 466 of file md49_base_controller_class.h.
Definition at line 467 of file md49_base_controller_class.h.
Definition at line 10 of file md49_base_controller_class.h.
char BaseController::reply[8] [private] |
Definition at line 454 of file md49_base_controller_class.h.
int BaseController::requested_speed_l [private] |
Definition at line 455 of file md49_base_controller_class.h.
int BaseController::requested_speed_r [private] |
requested speed_l and speed_r for MD49
Definition at line 455 of file md49_base_controller_class.h.
std::string BaseController::serialport [private] |
used serialport on pcDuino, is read from parameters server
Definition at line 461 of file md49_base_controller_class.h.
int BaseController::serialport_bps [private] |
used baudrate, is read from parameters server
Definition at line 462 of file md49_base_controller_class.h.
ros::Subscriber BaseController::sub_cmd_vel [private] |
Definition at line 464 of file md49_base_controller_class.h.