Fawkes API
Fawkes Development Version
|
Thread to communicate with Robotino via OpenRobotino API (v1 or v2). More...
#include "openrobotino_com_thread.h"
Public Member Functions | |
OpenRobotinoComThread () | |
Constructor. More... | |
virtual | ~OpenRobotinoComThread () |
Destructor. More... | |
virtual void | init () |
Initialize the thread. More... | |
virtual void | once () |
Execute an action exactly once. More... | |
virtual void | loop () |
Code to execute in the thread. More... | |
virtual void | finalize () |
Finalize the thread. More... | |
virtual bool | is_connected () |
Check if we are connected to OpenRobotino. More... | |
virtual void | set_gripper (bool opened) |
Open or close gripper. More... | |
virtual bool | is_gripper_open () |
Check if gripper is open. More... | |
virtual void | set_speed_points (float s1, float s2, float s3) |
Set speed points for wheels. More... | |
virtual void | get_act_velocity (float &a1, float &a2, float &a3, unsigned int &seq, fawkes::Time &t) |
Get actual velocity. More... | |
virtual void | get_odometry (double &x, double &y, double &phi) |
Get current odometry. More... | |
virtual void | reset_odometry () |
Reset odometry to zero. More... | |
virtual void | set_bumper_estop_enabled (bool enabled) |
Enable or disable emergency stop on bumper contact. More... | |
virtual void | set_motor_accel_limits (float min_accel, float max_accel) |
Set acceleration limits of motors. More... | |
virtual void | set_digital_output (unsigned int digital_out, bool enable) |
Set digital output state. More... | |
![]() | |
RobotinoComThread (const char *thread_name) | |
Constructor. More... | |
virtual | ~RobotinoComThread () |
Destructor. More... | |
virtual bool | get_data (SensorData &sensor_data) |
Get all current sensor data. More... | |
void | set_drive_layout (float rb, float rw, float gear) |
Set omni drive layout parameters. More... | |
void | set_drive_limits (float trans_accel, float trans_decel, float rot_accel, float rot_decel) |
Set the omni drive limits. More... | |
virtual void | set_desired_vel (float vx, float vy, float omega) |
Set desired velocities. More... | |
void | project (float *m1, float *m2, float *m3, float vx, float vy, float omega) const |
Project the velocity of the robot in cartesian coordinates to single motor speeds. More... | |
void | unproject (float *vx, float *vy, float *omega, float m1, float m2, float m3) const |
Project single motor speeds to velocity in cartesian coordinates. More... | |
![]() | |
virtual | ~Thread () |
Virtual destructor. More... | |
bool | prepare_finalize () |
Prepare finalization. More... | |
virtual bool | prepare_finalize_user () |
Prepare finalization user implementation. More... | |
void | cancel_finalize () |
Cancel finalization. More... | |
void | start (bool wait=true) |
Call this method to start the thread. More... | |
void | cancel () |
Cancel a thread. More... | |
void | join () |
Join the thread. More... | |
void | detach () |
Detach the thread. More... | |
void | kill (int sig) |
Send signal to a thread. More... | |
bool | operator== (const Thread &thread) |
Check if two threads are the same. More... | |
void | wakeup () |
Wake up thread. More... | |
void | wakeup (Barrier *barrier) |
Wake up thread and wait for barrier afterwards. More... | |
void | wait_loop_done () |
Wait for the current loop iteration to finish. More... | |
OpMode | opmode () const |
Get operation mode. More... | |
pthread_t | thread_id () const |
Get ID of thread. More... | |
bool | started () const |
Check if thread has been started. More... | |
bool | cancelled () const |
Check if thread has been cancelled. More... | |
bool | detached () const |
Check if thread has been detached. More... | |
bool | running () const |
Check if the thread is running. More... | |
bool | waiting () const |
Check if thread is currently waiting for wakeup. More... | |
const char * | name () const |
Get name of thread. More... | |
void | set_flags (uint32_t flags) |
Set all flags in one go. More... | |
void | set_flag (uint32_t flag) |
Set flag for the thread. More... | |
void | unset_flag (uint32_t flag) |
Unset flag. More... | |
bool | flagged_bad () const |
Check if FLAG_BAD was set. More... | |
void | set_delete_on_exit (bool del) |
Set whether the thread should be deleted on exit. More... | |
void | set_prepfin_hold (bool hold) |
Hold prepare_finalize(). More... | |
void | add_notification_listener (ThreadNotificationListener *notification_listener) |
Add notification listener. More... | |
void | remove_notification_listener (ThreadNotificationListener *notification_listener) |
Remove notification listener. More... | |
void | notify_of_failed_init () |
Notify of failed init. More... | |
![]() | |
ClockAspect () | |
Constructor. More... | |
virtual | ~ClockAspect () |
Virtual empty destructor. More... | |
void | init_ClockAspect (Clock *clock) |
Set the clock. More... | |
![]() | |
const std::list< const char * > & | get_aspects () const |
Get list of aspect names attached to a aspected thread. More... | |
![]() | |
LoggingAspect () | |
Constructor. More... | |
virtual | ~LoggingAspect () |
Virtual empty Destructor. More... | |
void | init_LoggingAspect (Logger *logger) |
Set the logger. More... | |
![]() | |
ConfigurableAspect () | |
Constructor. More... | |
virtual | ~ConfigurableAspect () |
Virtual empty Destructor. More... | |
void | init_ConfigurableAspect (Configuration *config) |
Set the configuration It is guaranteed that this is called for a configurable thread before Thread::start() is called (when running regularly inside Fawkes). More... | |
Protected Member Functions | |
virtual void | run () |
Stub to see name in backtrace for easier debugging. More... | |
![]() | |
bool | update_velocities () |
Update velocity values. More... | |
![]() | |
Thread (const char *name) | |
Constructor. More... | |
Thread (const char *name, OpMode op_mode) | |
Constructor. More... | |
void | exit () |
Exit the thread. More... | |
void | test_cancel () |
Set cancellation point. More... | |
void | yield () |
Yield the processor to another thread or process. More... | |
void | set_opmode (OpMode op_mode) |
Set operation mode. More... | |
void | set_prepfin_conc_loop (bool concurrent=true) |
Set concurrent execution of prepare_finalize() and loop(). More... | |
void | set_coalesce_wakeups (bool coalesce=true) |
Set wakeup coalescing. More... | |
void | set_name (const char *format,...) |
Set name of thread. More... | |
bool | wakeup_pending () |
Check if wakeups are pending. More... | |
![]() | |
void | add_aspect (const char *name) |
Add an aspect to a thread. More... | |
Additional Inherited Members | |
![]() | |
enum | OpMode { OPMODE_CONTINUOUS, OPMODE_WAITFORWAKEUP } |
Thread operation mode. More... | |
enum | CancelState { CANCEL_ENABLED, CANCEL_DISABLED } |
Cancel state. More... | |
![]() | |
static Thread * | current_thread () |
Get the Thread instance of the currently running thread. More... | |
static Thread * | current_thread_noexc () throw () |
Similar to current_thread, but does never throw an exception. More... | |
static pthread_t | current_thread_id () |
Get the ID of the currently running thread. More... | |
static void | init_main () |
Initialize Thread wrapper instance for main thread. More... | |
static void | destroy_main () |
Destroy main thread wrapper instance. More... | |
static void | set_cancel_state (CancelState new_state, CancelState *old_state=0) |
Set the cancel state of the current thread. More... | |
![]() | |
static const unsigned int | FLAG_BAD = 0x00000001 |
Standard thread flag: "thread is bad". More... | |
![]() | |
fawkes::Mutex * | data_mutex_ |
Mutex to protect data_. More... | |
SensorData | data_ |
Data struct that must be updated whenever new data is available. More... | |
bool | new_data_ |
Flag to indicate new data, set to true if data_ is modified. More... | |
![]() | |
bool | finalize_prepared |
True if prepare_finalize() has been called and was not stopped with a cancel_finalize(), false otherwise. More... | |
Mutex * | loop_mutex |
Mutex that is used to protect a call to loop(). More... | |
Mutex * | loopinterrupt_antistarve_mutex |
Mutex to avoid starvation when trying to lock loop_mutex. More... | |
![]() | |
Clock * | clock |
By means of this member access to the clock is given. More... | |
![]() | |
Logger * | logger |
This is the Logger member used to access the logger. More... | |
![]() | |
Configuration * | config |
This is the Configuration member used to access the configuration. More... | |
Thread to communicate with Robotino via OpenRobotino API (v1 or v2).
Definition at line 71 of file openrobotino_com_thread.h.
OpenRobotinoComThread::OpenRobotinoComThread | ( | ) |
Constructor.
Definition at line 58 of file openrobotino_com_thread.cpp.
|
virtual |
Destructor.
Definition at line 68 of file openrobotino_com_thread.cpp.
|
virtual |
Finalize the thread.
This method is executed just before the thread is canceled and destroyed. It is always preceeded by a call to prepare_finalize(). If this is not the case this is a failure. The condition can be checked with the boolean variable finalize_prepared.
This method is meant to be used in conjunction with aspects and to cover thread inter-dependencies. This routine MUST bring the thread into a safe state such that it may be canceled and destroyed afterwards. If there is any reason that this cannot happen make your prepare_finalize() reports so.
This method is called by the thread manager just before the thread is being cancelled. Here you can do whatever steps are necessary just before the thread is cancelled. Note that you thread is still running and might be in the middle of a loop, so it is not a good place to give up on all resources used. Mind segmentation faults that could happen. Protect the area with a mutex that you lock at the beginning of your loop and free in the end, and that you lock at the beginning of finalize and then never unlock. Also not that the finalization may be canceled afterwards. The next thing that happens is that either the thread is canceled and destroyed or that the finalization is canceled and the thread has to run again.
Finalize is called on a thread just before it is deleted. It is guaranteed to be called on a fully initialized thread (if no exception is thrown in init()) (this guarantee holds in the Fawkes framework).
The default implementation does nothing besides throwing an exception if prepare_finalize() has not been called.
Exception | thrown if prepare_finalize() has not been called. |
Reimplemented from fawkes::Thread.
Definition at line 142 of file openrobotino_com_thread.cpp.
|
virtual |
Get actual velocity.
a1 | upon return contains velocity in RPM for first wheel |
a2 | upon return contains velocity in RPM for second wheel |
a3 | upon return contains velocity in RPM for third wheel |
seq | upon return contains sequence number of latest data |
t | upon return contains time of latest data |
Implements RobotinoComThread.
Definition at line 416 of file openrobotino_com_thread.cpp.
References RobotinoComThread::data_mutex_, and fawkes::Time::stamp().
|
virtual |
Get current odometry.
x | X coordinate of robot in odometry frame |
y | Y coordinate of robot in odometry frame |
phi | orientation of robot in odometry frame |
Implements RobotinoComThread.
Definition at line 453 of file openrobotino_com_thread.cpp.
References RobotinoComThread::data_mutex_, and fawkes::deg2rad().
|
virtual |
Initialize the thread.
This method is meant to be used in conjunction with aspects. Some parts of the initialization may only happen after some aspect of the thread has been initialized. Implement the init method with these actions. It is guaranteed to be called just after all aspects have been initialized and only once in the lifetime of the thread. Throw an exception if any problem occurs and the thread should not run.
Just because your init() routine suceeds and everything looks fine for this thread does not automatically imply that it will run. If it belongs to a group of threads in a ThreadList and any of the other threads fail to initialize then no thread from this group is run and thus this thread will never run. In that situation finalize() is called for this very instance, prepare_finalize() however is not called.
Reimplemented from fawkes::Thread.
Definition at line 74 of file openrobotino_com_thread.cpp.
References fawkes::ClockAspect::clock, fawkes::ConfigurableAspect::config, RobotinoComThread::data_, fawkes::deg2rad(), fawkes::Configuration::get_bool(), fawkes::Configuration::get_string(), and fawkes::Configuration::get_uint().
|
virtual |
Check if we are connected to OpenRobotino.
Implements RobotinoComThread.
Definition at line 402 of file openrobotino_com_thread.cpp.
|
virtual |
Check if gripper is open.
Implements RobotinoComThread.
Definition at line 477 of file openrobotino_com_thread.cpp.
References RobotinoComThread::data_mutex_.
|
virtual |
Code to execute in the thread.
Implement this method to hold the code you want to be executed continously. If you do not implement this method, the default is that the thread will exit. This is useful if you choose to only implement once().
Reimplemented from fawkes::Thread.
Definition at line 179 of file openrobotino_com_thread.cpp.
References RobotinoComThread::data_, RobotinoComThread::data_mutex_, fawkes::Logger::log_error(), fawkes::Logger::log_warn(), fawkes::LoggingAspect::logger, fawkes::TimeWait::mark_start(), fawkes::Thread::name(), RobotinoComThread::new_data_, and fawkes::TimeWait::wait().
|
virtual |
Execute an action exactly once.
This code is executed once and only once right after the thread is started before loop() is called. This is useful if you want to implement an one-shot background job. Just implement once() and leave loop() untouched. Start the thread and detach it and it will just do its job and then die automatically. If you use set_delete_on_exit(true) even the Thread instance will be automatically deleted.
Reimplemented from fawkes::Thread.
Definition at line 173 of file openrobotino_com_thread.cpp.
References reset_odometry().
|
virtual |
Reset odometry to zero.
Implements RobotinoComThread.
Definition at line 370 of file openrobotino_com_thread.cpp.
Referenced by once().
|
inlineprotectedvirtual |
Stub to see name in backtrace for easier debugging.
Reimplemented from fawkes::Thread.
Definition at line 101 of file openrobotino_com_thread.h.
|
virtual |
Enable or disable emergency stop on bumper contact.
enabled | true to enable, false to disable |
Implements RobotinoComThread.
Definition at line 536 of file openrobotino_com_thread.cpp.
References fawkes::Logger::log_info(), fawkes::LoggingAspect::logger, and fawkes::Thread::name().
|
virtual |
Set digital output state.
digital_out | digital output as written on the robot, i.e., 1 to 8 |
enable | true to enable output, false to disable |
Implements RobotinoComThread.
Definition at line 392 of file openrobotino_com_thread.cpp.
References fawkes::Logger::log_error(), fawkes::LoggingAspect::logger, and fawkes::Thread::name().
|
virtual |
Open or close gripper.
opened | true to open gripper, false to close |
Implements RobotinoComThread.
Definition at line 519 of file openrobotino_com_thread.cpp.
|
virtual |
Set acceleration limits of motors.
min_accel | minimum acceleration |
max_accel | maximum acceleration |
Implements RobotinoComThread.
Definition at line 386 of file openrobotino_com_thread.cpp.
|
virtual |
Set speed points for wheels.
s1 | speed point for first wheel in RPM |
s2 | speed point for second wheel in RPM |
s3 | speed point for third wheel in RPM |
Implements RobotinoComThread.
Definition at line 499 of file openrobotino_com_thread.cpp.