#include <devsteer.h>
Public Member Functions | |
int | check_status (void) |
int | Close () |
int | Configure () |
int32_t | degrees2ticks (float degrees) |
devsteer (int32_t center=0) | |
int | get_angle (float °rees) |
int | Open () |
void | publish_diag (const ros::Publisher &diag_pub) |
int | set_initial_angle (float position) |
int | steering_absolute (float position) |
int | steering_relative (float position) |
float | ticks2degrees (int32_t ticks) |
~devsteer () | |
Private Member Functions | |
int | configure_steering (void) |
int | encoder_goto (float degrees) |
int | get_encoder (int32_t &iticks) |
int | get_status_word (uint16_t &status) |
int64_t | GetTime () |
int | send_cmd (const char *string) |
int | servo_cmd (const char *string) |
void | servo_write_only (const char *string) |
int | write_register (int reg, int32_t val) |
Private Attributes | |
bool | center_on_exit_ |
int32_t | center_ticks_ |
art_msgs::SteeringDiagnostics | diag_msg_ |
std::string | port_ |
float | req_angle_ |
bool | simulate_moving_errors_ |
float | starting_angle_ |
int32_t | starting_ticks_ |
double | steering_rate_ |
bool | training_ |
Definition at line 71 of file devsteer.h.
devsteer::devsteer | ( | int32_t | center = 0 |
) |
Definition at line 34 of file devsteer.cc.
devsteer::~devsteer | ( | ) | [inline] |
Definition at line 76 of file devsteer.h.
int devsteer::check_status | ( | void | ) |
check device status
Definition at line 110 of file devsteer.cc.
int devsteer::Close | ( | void | ) | [virtual] |
Reimplemented from Servo.
Definition at line 65 of file devsteer.cc.
int devsteer::Configure | ( | ) |
Definition at line 72 of file devsteer.cc.
int devsteer::configure_steering | ( | void | ) | [private] |
Definition at line 394 of file devsteer.cc.
int32_t devsteer::degrees2ticks | ( | float | degrees | ) | [inline] |
Definition at line 91 of file devsteer.h.
int devsteer::encoder_goto | ( | float | degrees | ) | [private] |
Definition at line 467 of file devsteer.cc.
int devsteer::get_angle | ( | float & | degrees | ) |
get steering angle
When running without actual steering controller, simulate the wheel motion.
degrees | current steering angle, if I/O successful |
Definition at line 144 of file devsteer.cc.
int devsteer::get_encoder | ( | int32_t & | iticks | ) | [private] |
get steering encoder value
iticks | set to encoder position, if I/O successful |
Definition at line 197 of file devsteer.cc.
int devsteer::get_status_word | ( | uint16_t & | status | ) | [private] |
Definition at line 226 of file devsteer.cc.
int64_t devsteer::GetTime | ( | ) | [private] |
Definition at line 28 of file devsteer.cc.
int devsteer::Open | ( | ) |
Definition at line 39 of file devsteer.cc.
void devsteer::publish_diag | ( | const ros::Publisher & | diag_pub | ) |
publish current diagnostic information
diag_pub | ROS publish object for SteeringDiagnostics message. |
Definition at line 266 of file devsteer.cc.
int devsteer::send_cmd | ( | const char * | string | ) | [private] |
Definition at line 491 of file devsteer.cc.
int devsteer::servo_cmd | ( | const char * | string | ) | [private] |
Definition at line 598 of file devsteer.cc.
void devsteer::servo_write_only | ( | const char * | string | ) | [private] |
Write a command to the Quicksilver, no response expected.
Definition at line 617 of file devsteer.cc.
int devsteer::set_initial_angle | ( | float | position | ) |
set the initial steering wheel angle
Definition at line 284 of file devsteer.cc.
int devsteer::steering_absolute | ( | float | position | ) |
Definition at line 375 of file devsteer.cc.
int devsteer::steering_relative | ( | float | position | ) |
Definition at line 382 of file devsteer.cc.
float devsteer::ticks2degrees | ( | int32_t | ticks | ) | [inline] |
Definition at line 97 of file devsteer.h.
int devsteer::write_register | ( | int | reg, | |
int32_t | val | |||
) | [private] |
Definition at line 478 of file devsteer.cc.
bool devsteer::center_on_exit_ [private] |
Definition at line 107 of file devsteer.h.
int32_t devsteer::center_ticks_ [private] |
Definition at line 116 of file devsteer.h.
art_msgs::SteeringDiagnostics devsteer::diag_msg_ [private] |
Definition at line 118 of file devsteer.h.
std::string devsteer::port_ [private] |
Definition at line 108 of file devsteer.h.
float devsteer::req_angle_ [private] |
Definition at line 113 of file devsteer.h.
bool devsteer::simulate_moving_errors_ [private] |
Definition at line 110 of file devsteer.h.
float devsteer::starting_angle_ [private] |
Definition at line 114 of file devsteer.h.
int32_t devsteer::starting_ticks_ [private] |
Definition at line 115 of file devsteer.h.
double devsteer::steering_rate_ [private] |
Definition at line 111 of file devsteer.h.
bool devsteer::training_ [private] |
Definition at line 109 of file devsteer.h.