#include <ros/ros.h>#include <sensor_msgs/Joy.h>#include <corobot_msgs/PanTilt.h>#include <stdio.h>#include <stdlib.h>#include <unistd.h>#include <string.h>#include <fcntl.h>#include <linux/videodev2.h>#include <sys/ioctl.h>#include <errno.h>#include <diagnostic_updater/diagnostic_updater.h>#include <diagnostic_updater/publisher.h>#include "dynctrl.h"
Go to the source code of this file.
Defines | |
| #define | BITS_PER_DEGREE (64) |
| #define | MAX_PAN_DEG (70) |
| #define | MAX_TILT_DEG (30) |
| #define | MIN_PAN_DEG (-70) |
| #define | MIN_STEP_DEG (2) |
| #define | MIN_TILT_DEG (-30) |
Functions | |
| void | joyCallback (const sensor_msgs::JoyConstPtr &msg) |
| int | main (int argc, char **argv) |
| void | pantilt_check_speed (int fd) |
| void | pantilt_diagnostic (diagnostic_updater::DiagnosticStatusWrapper &stat) |
| int | pantilt_move (int fd, int pan, int tilt) |
| int | pantilt_reset (int fd) |
| void | pantiltCallback (const corobot_msgs::PanTiltConstPtr &msg) |
Variables | |
| static int | cam_fd |
| int | pantiltError = 0 |
| #define BITS_PER_DEGREE (64) |
Definition at line 61 of file pantilt.cpp.
| #define MAX_PAN_DEG (70) |
Definition at line 62 of file pantilt.cpp.
| #define MAX_TILT_DEG (30) |
Definition at line 64 of file pantilt.cpp.
| #define MIN_PAN_DEG (-70) |
Definition at line 63 of file pantilt.cpp.
| #define MIN_STEP_DEG (2) |
Definition at line 66 of file pantilt.cpp.
| #define MIN_TILT_DEG (-30) |
Definition at line 65 of file pantilt.cpp.
| void joyCallback | ( | const sensor_msgs::JoyConstPtr & | msg | ) |
called everytime a joy message is received.
Definition at line 89 of file pantilt.cpp.
| int main | ( | int | argc, |
| char ** | argv | ||
| ) |
Definition at line 155 of file pantilt.cpp.
| void pantilt_check_speed | ( | int | fd | ) |
Definition at line 201 of file pantilt.cpp.
| void pantilt_diagnostic | ( | diagnostic_updater::DiagnosticStatusWrapper & | stat | ) |
Function that will report the status of the hardware to the diagnostic topic
Definition at line 136 of file pantilt.cpp.
| int pantilt_move | ( | int | fd, |
| int | pan, | ||
| int | tilt | ||
| ) |
Definition at line 242 of file pantilt.cpp.
| int pantilt_reset | ( | int | fd | ) |
Definition at line 229 of file pantilt.cpp.
| void pantiltCallback | ( | const corobot_msgs::PanTiltConstPtr & | msg | ) |
Definition at line 75 of file pantilt.cpp.
int cam_fd [static] |
Definition at line 72 of file pantilt.cpp.
| int pantiltError = 0 |
Definition at line 73 of file pantilt.cpp.