#include <cstdio>
#include <ros/ros.h>
#include <ros/time.h>
#include "uvc_cam/uvc_cam.h"
#include "sensor_msgs/CameraInfo.h"
#include "sensor_msgs/Image.h"
#include "sensor_msgs/CompressedImage.h"
#include "sensor_msgs/image_encodings.h"
#include <camera_calibration_parsers/parse_ini.h>
#include <dynamic_reconfigure/server.h>
#include <corobot_camera/corobot_cameraConfig.h>
#include <diagnostic_updater/diagnostic_updater.h>
#include <diagnostic_updater/publisher.h>
#include "corobot_diagnostics/diagnostics.h"
#include <image_transport/image_transport.h>
#include <opencv/cvwimage.h>
#include <opencv/highgui.h>
#include "std_msgs/String.h"
#include "corobot_msgs/videomode.h"
#include "corobot_msgs/state.h"
Go to the source code of this file.
Enumerations | |
enum | e_state { PLAYING, STOP, CHANGE_MODE } |
Functions | |
void | dynamic_reconfigureCallback (corobot_camera::corobot_cameraConfig &config, uint32_t level) |
int | is_huffman (unsigned char *buf) |
int | main (int argc, char **argv) |
void | mainloop (const char *device, int width, int height, int fps, ros::NodeHandle n, image_transport::CameraPublisher pub, diagnostic_updater::Updater &updater) |
void | stateCallback (const corobot_msgs::state::ConstPtr &msg) |
void | videomodeCallback (const corobot_msgs::videomode::ConstPtr &msg) |
void | webcam_diagnostic (diagnostic_updater::DiagnosticStatusWrapper &stat) |
Variables | |
enum e_state | __attribute__ |
bool | auto_exposure = true |
uvc_cam::Cam * | cam_ptr |
bool | camera_activated = true |
sensor_msgs::CameraInfo::Ptr | camera_info |
int | camera_state = 0 |
static const unsigned char | dht_data [] |
ros::Publisher | image_pub |
bool | isjpeg = false |
int | new_fps |
int | new_height |
int | new_width |
char | state = STOP |
enum e_state |
Definition at line 67 of file dynamic_sender.cpp.
void dynamic_reconfigureCallback | ( | corobot_camera::corobot_cameraConfig & | config, |
uint32_t | level | ||
) |
Dynamic reconfigure callback
Definition at line 312 of file dynamic_sender.cpp.
int is_huffman | ( | unsigned char * | buf | ) |
Definition at line 163 of file dynamic_sender.cpp.
int main | ( | int | argc, |
char ** | argv | ||
) |
Definition at line 349 of file dynamic_sender.cpp.
void mainloop | ( | const char * | device, |
int | width, | ||
int | height, | ||
int | fps, | ||
ros::NodeHandle | n, | ||
image_transport::CameraPublisher | pub, | ||
diagnostic_updater::Updater & | updater | ||
) |
Definition at line 181 of file dynamic_sender.cpp.
void stateCallback | ( | const corobot_msgs::state::ConstPtr & | msg | ) |
Definition at line 94 of file dynamic_sender.cpp.
void videomodeCallback | ( | const corobot_msgs::videomode::ConstPtr & | msg | ) |
Definition at line 110 of file dynamic_sender.cpp.
void webcam_diagnostic | ( | diagnostic_updater::DiagnosticStatusWrapper & | stat | ) |
Function that will report the status of the hardware to the diagnostic topic
Definition at line 320 of file dynamic_sender.cpp.
struct avi_t __attribute__ |
bool auto_exposure = true |
Definition at line 74 of file dynamic_sender.cpp.
Definition at line 86 of file dynamic_sender.cpp.
bool camera_activated = true |
Definition at line 77 of file dynamic_sender.cpp.
sensor_msgs::CameraInfo::Ptr camera_info |
Definition at line 63 of file dynamic_sender.cpp.
int camera_state = 0 |
Definition at line 80 of file dynamic_sender.cpp.
const unsigned char dht_data[] [static] |
Definition at line 123 of file dynamic_sender.cpp.
Definition at line 64 of file dynamic_sender.cpp.
bool isjpeg = false |
Definition at line 83 of file dynamic_sender.cpp.
int new_fps |
Definition at line 71 of file dynamic_sender.cpp.
int new_height |
Definition at line 71 of file dynamic_sender.cpp.
int new_width |
Definition at line 71 of file dynamic_sender.cpp.
Definition at line 68 of file dynamic_sender.cpp.