#include <ros/ros.h>#include <std_msgs/Float64.h>#include <strstream>#include <sstream>#include <exception>#include <boost/thread.hpp>#include <sensor_msgs/JointState.h>#include "image_transport/subscriber.h"#include "sensor_msgs/Image.h"#include <image_transport/image_transport.h>#include <opencv2/highgui/highgui.hpp>#include <cv_bridge/cv_bridge.h>#include "opencv2/imgproc/imgproc.hpp"#include <sensor_msgs/image_encodings.h>#include <std_msgs/Float64MultiArray.h>

Go to the source code of this file.
Classes | |
| class | VisualServoController |
Defines | |
| #define | CAMERA_DATA_SIZE 20 |
| #define | DOF 4 |
| #define | JOINTS_ERROR 0.01 |
| #define | JOINTS_NUM 6 |
| #define | KERNEL_SIZE 4 |
| #define | L1 0.3 |
| #define | L2 0.25 |
| #define | L3 0.16 |
| #define | L5 0.072 |
| #define | LAMBDA_THETA -0.01 |
| #define | LAMBDA_X 200 |
| #define | LAMBDA_Y 200 |
| #define | LAMBDA_Z 200 |
| #define | SAMPLE_TIME 0.01 |
| #define CAMERA_DATA_SIZE 20 |
Definition at line 22 of file aras_visual_servo_controller.h.
| #define DOF 4 |
Definition at line 20 of file aras_visual_servo_controller.h.
| #define JOINTS_ERROR 0.01 |
Definition at line 34 of file aras_visual_servo_controller.h.
| #define JOINTS_NUM 6 |
Definition at line 18 of file aras_visual_servo_controller.h.
| #define KERNEL_SIZE 4 |
Definition at line 19 of file aras_visual_servo_controller.h.
| #define L1 0.3 |
Definition at line 29 of file aras_visual_servo_controller.h.
| #define L2 0.25 |
Definition at line 30 of file aras_visual_servo_controller.h.
| #define L3 0.16 |
Definition at line 31 of file aras_visual_servo_controller.h.
| #define L5 0.072 |
Definition at line 32 of file aras_visual_servo_controller.h.
| #define LAMBDA_THETA -0.01 |
Definition at line 27 of file aras_visual_servo_controller.h.
| #define LAMBDA_X 200 |
Definition at line 24 of file aras_visual_servo_controller.h.
| #define LAMBDA_Y 200 |
Definition at line 25 of file aras_visual_servo_controller.h.
| #define LAMBDA_Z 200 |
Definition at line 26 of file aras_visual_servo_controller.h.
| #define SAMPLE_TIME 0.01 |
Definition at line 33 of file aras_visual_servo_controller.h.