Public Member Functions | |
| P2OS (ConfigFile *cf, int section) | |
| virtual int | Subscribe (player_devaddr_t id) |
| Subscribe to this driver. | |
| virtual int | Unsubscribe (player_devaddr_t id) |
| Unsubscribe from this driver. | |
| virtual void | Main () |
| Main method for driver thread. | |
| virtual int | MainSetup () |
| Sets up the resources needed by the driver thread. | |
| virtual void | MainQuit () |
| Cleanup method for driver thread (called when main exits) | |
| virtual int | ProcessMessage (QueuePointer &resp_queue, player_msghdr *hdr, void *data) |
| Message handler. | |
| void | CMUcamReset (bool doLock=true) |
| void | CMUcamTrack (int rmin=0, int rmax=0, int gmin=0, int gmax=0, int bmin=0, int bmax=0) |
| void | CMUcamStartTracking (bool doLock=true) |
| void | CMUcamStopTracking (bool doLock=true) |
Private Member Functions | |
| int | SendReceive (P2OSPacket *pkt, bool publish_data=true) |
| void | ResetRawPositions () |
| void | ToggleSonarPower (unsigned char val) |
| void | ToggleMotorPower (unsigned char val) |
| int | HandleConfig (QueuePointer &resp_queue, player_msghdr *hdr, void *data) |
| int | HandleCommand (player_msghdr *hdr, void *data) |
| void | StandardSIPPutData (double timestampStandardSIP) |
| void | GyroPutData (double timestampGyro) |
| void | BlobfinderPutData (double timestampSERAUX) |
| void | ActarrayPutData (double timestampArm) |
| void | HandlePositionCommand (player_position2d_cmd_vel_t position_cmd) |
| int | HandleGripperCommand (player_msghdr *hdr, void *data) |
| int | HandleLiftCommand (player_msghdr *hdr, void *data) |
| int | HandleArmGripperCommand (player_msghdr *hdr, void *data) |
| void | HandleAudioCommand (player_audio_sample_item_t audio_cmd) |
| void | get_ptz_packet (int s1, int s2=0) |
| int | SetupPtz () |
| void | OpenGripper (void) |
| void | CloseGripper (void) |
| void | StopGripper (void) |
| void | OpenArmGripper (void) |
| void | CloseArmGripper (void) |
| void | StopArmGripper (void) |
| double | TicksToDegrees (int joint, unsigned char ticks) |
| unsigned char | DegreesToTicks (int joint, double degrees) |
| double | TicksToRadians (int joint, unsigned char ticks) |
| unsigned char | RadiansToTicks (int joint, double rads) |
| double | RadsPerSectoSecsPerTick (int joint, double speed) |
| double | SecsPerTicktoRadsPerSec (int joint, double secs) |
| void | ToggleActArrayPower (unsigned char val, bool lock=true) |
| void | SetActArrayJointSpeed (int joint, double speed) |
| void | HandleActArrayPosCmd (player_actarray_position_cmd_t cmd) |
| void | HandleActArrayHomeCmd (player_actarray_home_cmd_t cmd) |
| int | HandleActArrayCommand (player_msghdr *hdr, void *data) |
| void | HandleLimbHomeCmd (void) |
| void | HandleLimbStopCmd (void) |
| void | HandleLimbSetPoseCmd (player_limb_setpose_cmd_t cmd) |
| void | HandleLimbSetPositionCmd (player_limb_setposition_cmd_t cmd) |
| void | HandleLimbVecMoveCmd (player_limb_vecmove_cmd_t cmd) |
| int | HandleLimbCommand (player_msghdr *hdr, void *data) |
| int | SendCommand (unsigned char *str, int len) |
| int | SendRequest (unsigned char *str, int len, unsigned char *reply, uint8_t camera=1) |
| void | PrintPacket (char *str, unsigned char *cmd, int len) |
| int | SendAbsPanTilt (int pan, int tilt) |
| int | setDefaultTiltRange () |
| int | GetAbsPanTilt (int *pan, int *tilt) |
| int | GetAbsZoom (int *zoom) |
| int | SendAbsZoom (int zoom) |
| int | read_ptz (unsigned char *reply, int size) |
| int | ReceiveCommandAnswer (int asize) |
| int | ReceiveRequestAnswer (unsigned char *data, int s1, int s2) |
| int | setControlMode () |
| int | setNotifyCommand () |
| int | setPower (int on) |
| int | setOnScreenOff () |
| int | CheckHostControlMode () |
| int | sendInit () |
| int | GetMaxZoom (int *maxzoom) |
| void | SendPulse (void) |
Private Attributes | |
| player_p2os_data_t | p2os_data |
| player_devaddr_t | position_id |
| player_devaddr_t | sonar_id |
| player_devaddr_t | aio_id |
| player_devaddr_t | dio_id |
| player_devaddr_t | gripper_id |
| player_devaddr_t | lift_id |
| player_devaddr_t | bumper_id |
| player_devaddr_t | power_id |
| player_devaddr_t | compass_id |
| player_devaddr_t | gyro_id |
| player_devaddr_t | blobfinder_id |
| player_devaddr_t | audio_id |
| player_devaddr_t | actarray_id |
| player_devaddr_t | limb_id |
| player_devaddr_t | ptz_id |
| player_devaddr_t | armgripper_id |
| bool | sentGripperCmd |
| uint8_t | lastGripperCmd |
| uint8_t | lastLiftCmd |
| player_actarray_position_cmd_t | lastLiftPosCmd |
| bool | sentArmGripperCmd |
| uint8_t | lastArmGripperCmd |
| uint8_t | lastActArrayCmd |
| player_actarray_position_cmd_t | lastActArrayPosCmd |
| player_actarray_home_cmd_t | lastActArrayHomeCmd |
| bool | sent_audio_cmd |
| player_audio_sample_item_t | last_audio_cmd |
| int | rot_kp |
| int | rot_kv |
| int | rot_ki |
| int | trans_kp |
| int | trans_kv |
| int | trans_ki |
| int | position_subscriptions |
| int | sonar_subscriptions |
| int | actarray_subscriptions |
| int | ptz_subscriptions |
| SIP * | sippacket |
| player_pose3d_t | gripperPose |
| player_bbox3d_t | gripperOuterSize |
| player_bbox3d_t | gripperInnerSize |
| player_bbox3d_t | armGripperOuterSize |
| player_bbox3d_t | armGripperInnerSize |
| double | aaLengths [6] |
| double | aaOrients [18] |
| double | aaAxes [18] |
| player_point_3d_t | aaBasePos |
| player_orientation_3d_t | aaBaseOrient |
| KineCalc * | kineCalc |
| float | armOffsetX |
| float | armOffsetY |
| float | armOffsetZ |
| player_limb_data_t | limb_data |
| int | param_idx |
| int | direct_wheel_vel_control |
| int | psos_fd |
| const char * | psos_serial_port |
| bool | psos_use_tcp |
| const char * | psos_tcp_host |
| int | psos_tcp_port |
| struct timeval | lastblob_tv |
| int | motor_max_speed |
| int | motor_max_turnspeed |
| bool | use_vel_band |
| short | motor_max_trans_accel |
| short | motor_max_trans_decel |
| short | motor_max_rot_accel |
| short | motor_max_rot_decel |
| int | radio_modemp |
| int | joystickp |
| int | bumpstall |
| bool | ignore_checksum |
| player_ptz_data_t | ptz_data |
| int | maxfov |
| int | minfov |
| int | maxzoom |
| int | pandemand |
| int | tiltdemand |
| int | zoomdemand |
| circbuf | cb |
| float | pulse |
| double | lastPulseTime |
Member Function Documentation
| void P2OS::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 Driver::InQueue, player_devaddr::interf, player_ptz_data::pan, Driver::ProcessMessages(), player_ptz_data::tilt, and player_ptz_data::zoom.
| void P2OS::MainQuit | ( | void | ) | [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.
References player_devaddr::interf.
| int P2OS::ProcessMessage | ( | QueuePointer & | resp_queue, |
| player_msghdr * | hdr, | ||
| void * | data | ||
| ) | [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_ACTARRAY_CMD_HOME, PLAYER_ACTARRAY_CMD_MULTI_POS, PLAYER_ACTARRAY_CMD_POS, PLAYER_ACTARRAY_REQ_GET_GEOM, PLAYER_ACTARRAY_REQ_POWER, PLAYER_ACTARRAY_REQ_SPEED, PLAYER_GRIPPER_CMD_CLOSE, PLAYER_GRIPPER_CMD_OPEN, PLAYER_GRIPPER_CMD_STOP, PLAYER_LIMB_CMD_HOME, PLAYER_LIMB_CMD_SETPOSE, PLAYER_LIMB_CMD_STOP, PLAYER_LIMB_REQ_GEOM, PLAYER_LIMB_REQ_POWER, PLAYER_MSGTYPE_CMD, PLAYER_MSGTYPE_REQ, PLAYER_POSITION2D_CMD_VEL, and player_msghdr::type.
| int P2OS::Subscribe | ( | player_devaddr_t | addr | ) | [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().
| int P2OS::Unsubscribe | ( | player_devaddr_t | addr | ) | [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(), and Driver::Unsubscribe().
The documentation for this class was generated from the following files:
- p2os.h
- p2os.cc
