Public Member Functions | |
wbr914 (ConfigFile *cf, int section) | |
virtual | ~wbr914 () |
Clean up any resources. | |
virtual int | Subscribe (player_devaddr_t id) |
Subscribe to this driver. More... | |
virtual int | Unsubscribe (player_devaddr_t id) |
Unsubscribe from this driver. More... | |
virtual void | Main () |
Main method for driver thread. More... | |
virtual int | MainSetup () |
Sets up the resources needed by the driver thread. | |
virtual void | MainQuit () |
Cleanup method for driver thread (called when main exits) More... | |
virtual int | ProcessMessage (QueuePointer &resp_queue, player_msghdr *hdr, void *data) |
Message handler. More... | |
Public Member Functions inherited from ThreadedDriver | |
ThreadedDriver (ConfigFile *cf, int section, bool overwrite_cmds, size_t queue_maxlen, int interface_) | |
Constructor with implicit interface. More... | |
ThreadedDriver (ConfigFile *cf, int section, bool overwrite_cmds=true, size_t queue_maxlen=PLAYER_MSGQUEUE_DEFAULT_MAXLEN) | |
Constructor for multiple-interface drivers. More... | |
virtual | ~ThreadedDriver () |
Destructor. | |
virtual int | Setup () |
Initialize the driver. More... | |
virtual int | Shutdown () |
Finalize the driver. More... | |
virtual int | Terminate () |
Terminate the driver. More... | |
bool | Wait (double TimeOut=0.0) |
Wait for new data to arrive on the driver's queue. More... | |
virtual void | Update () |
Update non-threaded drivers. More... | |
Public Member Functions inherited from Driver | |
bool | HasSubscriptions () |
virtual void | Publish (player_devaddr_t addr, QueuePointer &queue, uint8_t type, uint8_t subtype, void *src=NULL, size_t deprecated=0, double *timestamp=NULL, bool copy=true) |
Publish a message via one of this driver's interfaces. More... | |
virtual void | Publish (player_devaddr_t addr, uint8_t type, uint8_t subtype, void *src=NULL, size_t deprecated=0, double *timestamp=NULL, bool copy=true) |
Publish a message via one of this driver's interfaces. More... | |
virtual void | Publish (QueuePointer &queue, player_msghdr_t *hdr, void *src, bool copy=true) |
Publish a message via one of this driver's interfaces. More... | |
virtual void | Publish (player_msghdr_t *hdr, void *src, bool copy=true) |
Publish a message via one of this driver's interfaces. More... | |
Driver (ConfigFile *cf, int section, bool overwrite_cmds, size_t queue_maxlen, int interf) | |
Constructor for single-interface drivers. More... | |
Driver (ConfigFile *cf, int section, bool overwrite_cmds=true, size_t queue_maxlen=PLAYER_MSGQUEUE_DEFAULT_MAXLEN) | |
Constructor for multiple-interface drivers. More... | |
virtual | ~Driver () |
Destructor. | |
int | GetError () |
Get last error value. More... | |
virtual int | Subscribe (QueuePointer &, player_devaddr_t) |
Subscribe to this driver. More... | |
virtual int | Unsubscribe (QueuePointer &, player_devaddr_t) |
Unsubscribe from this driver. More... | |
void | ProcessMessages (int maxmsgs) |
Process pending messages. More... | |
void | ProcessMessages (void) |
Process pending messages. More... | |
virtual int | ProcessInternalMessages (QueuePointer &resp_queue, player_msghdr *hdr, void *data) |
Internal message handler. More... | |
virtual bool | RegisterProperty (const char *key, Property *property, ConfigFile *cf, int section) |
Property registration. More... | |
virtual bool | RegisterProperty (Property *property, ConfigFile *cf, int section) |
Property registration. More... | |
Private Member Functions | |
bool | RecvBytes (unsigned char *s, int len) |
int | ReadBuf (unsigned char *s, size_t len) |
int | WriteBuf (unsigned char *s, size_t len) |
int | sendCmdCom (unsigned char address, unsigned char c, int cmd_num, unsigned char *arg, int ret_num, unsigned char *ret) |
int | sendCmd0 (unsigned char address, unsigned char c, int ret_num, unsigned char *ret) |
int | sendCmd16 (unsigned char address, unsigned char c, int16_t arg, int ret_num, unsigned char *ret) |
int | sendCmd32 (unsigned char address, unsigned char c, int32_t arg, int ret_num, unsigned char *ret) |
int32_t | BytesToInt32 (unsigned char *ptr) |
int16_t | BytesToInt16 (unsigned char *ptr) |
int | ResetRawPositions () |
int | HandleConfig (QueuePointer &resp_queue, player_msghdr *hdr, void *data) |
int | HandleCommand (player_msghdr *hdr, void *data) |
void | HandleVelocityCommand (player_position2d_cmd_vel_t *cmd) |
void | HandleDigitalOutCommand (player_dio_data_t *doutCmd) |
void | SetDigitalData (player_dio_data_t *d) |
void | GetAllData (void) |
void | GetPositionData (player_position2d_data_t *d) |
void | GetIRData (player_ir_data_t *d) |
void | GetAnalogData (player_aio_data_t *d) |
void | GetDigitalData (player_dio_data_t *d) |
void | PublishData (void) |
const char * | GetPMDErrorString (int rc) |
int | InitRobot () |
void | UpdateM3 () |
void | Stop (int StopMode) |
bool | EnableMotors (bool enable) |
void | SetVelocity (uint8_t chan, float mps) |
void | SetVelocity (float mpsL, float mpsR) |
void | SetVelocityInTicks (int32_t left, int32_t right) |
void | GetVelocityInTicks (int32_t *left, int32_t *right) |
void | Move (uint8_t chan, float meters) |
void | Move (float metersL, float metersR) |
void | SetPosition (uint8_t chan, float meters) |
void | SetPosition (float metersL, float metersR) |
void | SetActualPositionInTicks (int32_t left, int32_t right) |
void | SetActualPosition (float left, float right) |
void | GetPositionInTicks (int32_t *left, int32_t *right) |
void | SetAccelerationProfile () |
void | StopRobot () |
int | GetAnalogSensor (int s, short *val) |
void | GetDigitalIn (unsigned short *digIn) |
void | SetDigitalOut (unsigned short digOut) |
void | SetOdometry (player_position2d_set_odom_req_t *od) |
void | SetContourMode (ProfileMode_t prof) |
void | SetMicrosteps () |
int32_t | Meters2Ticks (float meters) |
float | Ticks2Meters (int32_t ticks) |
int32_t | MPS2Vel (float mps) |
float | Vel2MPS (int32_t vel) |
Private Attributes | |
struct termios | _old_tio |
bool | _tioChanged |
int | _fd |
bool | _fd_blocking |
const char * | _serial_port |
int | _baud |
player_data_t | _data |
player_devaddr_t | position_id |
player_devaddr_t | ir_id |
player_devaddr_t | aio_id |
player_devaddr_t | dio_id |
int | position_subscriptions |
int | ir_subscriptions |
int | aio_subscriptions |
int | dio_subscriptions |
int | param_idx |
int | direct_wheel_vel_control |
player_position2d_cmd_vel_t | last_position_cmd |
int | motor_max_speed |
int | motor_max_turnspeed |
short | motor_max_trans_accel |
short | motor_max_trans_decel |
short | motor_max_rot_accel |
short | motor_max_rot_decel |
player_position2d_geom_t | _robot2d_geom |
player_position3d_geom_t | _robot3d_geom |
player_ir_pose_t | _ir_geom |
int32_t | last_lpos |
int32_t | last_rpos |
double | _x |
double | _y |
double | _yaw |
bool | _stopped |
bool | _motorsEnabled |
int | _debug |
int | _usCycleTime |
double | _velocityK |
double | _positionK |
int | _percentTorque |
uint16_t | _lastDigOut |
Additional Inherited Members | |
Public Attributes inherited from Driver | |
QueuePointer | ret_queue |
Last requester's queue. More... | |
player_devaddr_t | device_addr |
Default device address (single-interface drivers) | |
int | entries |
Total number of entries in the device table using this driver. More... | |
bool | alwayson |
Always on flag. More... | |
QueuePointer | InQueue |
Queue for all incoming messages for this driver. | |
Protected Member Functions inherited from ThreadedDriver | |
virtual void | StartThread (void) |
virtual void | StopThread (void) |
Cancel (and wait for termination) of the driver thread. More... | |
void | TestCancel () |
enable thread cancellation and test for cancellation More... | |
Protected Member Functions inherited from Driver | |
int | AddInterface (player_devaddr_t addr) |
Add an interface. More... | |
int | AddInterface (player_devaddr_t *addr, ConfigFile *cf, int section, int code, const char *key=NULL) |
Add an interface. More... | |
void | SetError (int code) |
Set/reset error code. | |
int | AddFileWatch (int fd, bool ReadWatch=true, bool WriteWatch=false, bool ExceptWatch=true) |
Wake up the driver if the specified event occurs on the file descriptor. | |
int | RemoveFileWatch (int fd, bool ReadWatch=true, bool WriteWatch=false, bool ExceptWatch=true) |
Remove a previously added watch, call with the same arguments as when adding the watch. | |
virtual void | Lock (void) |
Lock access between the server and driver threads. More... | |
virtual void | Unlock (void) |
Unlock access to driver internals. More... | |
virtual void | SubscriptionLock (void) |
Lock to protect the subscription count for the driver. | |
virtual void | SubscriptionUnlock (void) |
Unlock to protect the subscription count for the driver. More... | |
Static Protected Member Functions inherited from ThreadedDriver | |
static void * | DummyMain (void *driver) |
Dummy main (just calls real main). More... | |
static void | DummyMainQuit (void *driver) |
Dummy main cleanup (just calls real main cleanup). More... | |
Member Function Documentation
◆ Main()
|
virtual |
Main method for driver thread.
drivers have their own thread of execution, created using StartThread(); this is the entry point for the driver thread, and must be overloaded by all threaded drivers.
Implements ThreadedDriver.
References PLAYER_MSG0.
◆ MainQuit()
|
virtual |
Cleanup method for driver thread (called when main exits)
Overload this method and to do additional cleanup when the driver thread exits.
Reimplemented from ThreadedDriver.
◆ ProcessMessage()
|
virtual |
Message handler.
This function is called once for each message in the incoming queue. Reimplement it to provide message handling. Return 0 if you handled the message and -1 otherwise
- Parameters
-
resp_queue The queue to which any response should go. hdr The message header data The message body
Reimplemented from Driver.
References player_dio_data::bits, player_dio_data::count, Message::MatchMessage(), player_pose2d::pa, PLAYER_DIO_CMD_VALUES, PLAYER_IR_REQ_POSE, PLAYER_MSGTYPE_CMD, PLAYER_MSGTYPE_REQ, PLAYER_MSGTYPE_RESP_ACK, PLAYER_POSITION2D_CMD_VEL, PLAYER_POSITION2D_REQ_GET_GEOM, PLAYER_POSITION2D_REQ_MOTOR_POWER, PLAYER_POSITION2D_REQ_RESET_ODOM, PLAYER_POSITION2D_REQ_SET_ODOM, PLAYER_WARN, player_position2d_data::pos, player_position2d_set_odom_req::pose, player_pose2d::px, player_pose2d::py, player_ir_data::ranges, player_ir_data::ranges_count, player_msghdr::size, player_position2d_power_config::state, player_msghdr::subtype, player_msghdr::type, player_position2d_data::vel, player_position2d_cmd_vel::vel, player_aio_data::voltages, player_ir_data::voltages, and player_aio_data::voltages_count.
◆ Subscribe()
|
virtual |
Subscribe to this driver.
The Subscribe() and Unsubscribe() methods are used to control subscriptions to the driver; a driver MAY override them, but usually won't.
- Parameters
-
addr Address of the device to subscribe to (the driver may have more than one interface).
- Returns
- Returns 0 on success.
Reimplemented from Driver.
References Device::MatchDeviceAddress(), and Driver::Subscribe().
◆ Unsubscribe()
|
virtual |
Unsubscribe from this driver.
The Subscribe() and Unsubscribe() methods are used to control subscriptions to the driver; a driver MAY override them, but usually won't.
- Parameters
-
addr Address of the device to unsubscribe from (the driver may have more than one interface).
- Returns
- Returns 0 on success.
Reimplemented from Driver.
References Device::MatchDeviceAddress(), PLAYER_AIO_DATA_STATE, PLAYER_DIO_DATA_VALUES, PLAYER_IR_DATA_RANGES, PLAYER_MSGTYPE_DATA, PLAYER_POSITION2D_DATA_STATE, and Driver::Unsubscribe().
The documentation for this class was generated from the following files:
- wbr914.h
- wbr914.cc