22#if defined HAVE_CANLIB
23#include "canio_kvaser.h"
26#include "usb_packet.h"
27#include <libplayercore/playercore.h>
30typedef enum { UNKNOWN, RS232, CANBUS, USB } BusType;
33#define SPEEDTHRESH 0.01
64 player_position2d_data_t position_data;
68 player_position3d_data_t position3d_data;
72 player_power_data_t power_base_data;
76 player_power_data_t power_ui_data;
82 const char* caniotype;
83 const char* usb_device;
87 float max_xspeed, max_yawspeed;
94 float curr_xspeed, curr_yawspeed;
95 float last_xspeed, last_yawspeed;
102 bool motor_allow_enable;
108 uint32_t last_raw_yaw, last_raw_left, last_raw_right, last_raw_foreaft;
111 double odom_x, odom_y, odom_yaw;
114 int HandlePositionConfig(
QueuePointer &resp_queue, uint32_t subtype,
void* data,
size_t len);
117 int HandlePosition3DConfig(
QueuePointer &resp_queue, uint32_t subtype,
void* data,
size_t len);
126 int Diff(uint32_t from, uint32_t to,
bool first);
135 void MakeStatusCommand(
CanPacket* pkt, uint16_t cmd, uint16_t val);
138 void MakeVelocityCommand(
CanPacket* pkt, int32_t xspeed, int32_t yawspeed);
140 void MakeShutdownCommand(
CanPacket* pkt);
Class for loading configuration file information.
Definition configfile.h:197
An autopointer for the message queue.
Definition message.h:74
Definition segwayrmp.h:41
void UpdateData(rmp_frame_t *)
Definition segwayrmp.cc:999
virtual int ProcessMessage(QueuePointer &resp_queue, player_msghdr *hdr, void *data)
Message handler.
Definition segwayrmp.cc:589
virtual void Main()
Main method for driver thread.
Definition segwayrmp.cc:421
int USBSetup()
Sets up the USB bus for communication.
Definition segwayrmp.cc:368
int CanBusSetup()
Sets up the CAN bus for communication.
Definition segwayrmp.cc:341
virtual int MainSetup()
Sets up the resources needed by the driver thread.
Definition segwayrmp.cc:298
virtual void MainQuit()
Cleanup method for driver thread (called when main exits)
Definition segwayrmp.cc:388
Base class for drivers which oeprate with a thread.
Definition driver.h:553
Definition usb_packet.h:71
Definition rmp_frame.h:68
A device address.
Definition player.h:146
Generic message header.
Definition player.h:162