#include "ros/ros.h"
#include "geometry_msgs/Twist.h"
#include "gazebo_msgs/SetModelState.h"
#include "gazebo_msgs/GetModelState.h"
#include "sensor_msgs/CameraInfo.h"
#include <image_transport/image_transport.h>
#include "std_msgs/String.h"
#include <sensor_msgs/Image.h>
#include <sensor_msgs/image_encodings.h>
#include <cv_bridge/cv_bridge.h>
#include <opencv2/opencv.hpp>
#include <opencv2/core/core.hpp>
#include <opencv2/highgui/highgui.hpp>
#include <opencv2/imgproc/imgproc.hpp>
#include <stdio.h>
#include <stdlib.h>
#include <fstream>
#include <sstream>
#include <sys/types.h>
#include <netinet/in.h>
#include <sys/socket.h>
#include <sys/wait.h>
#include <pthread.h>
#include <netinet/tcp.h>
Go to the source code of this file.
Classes | |
struct | PositionInGazebo |
Macros | |
#define | BACKLOG 10 |
#define | PI 3.1415926 |
#define | SERVPORT 3333 |
Functions | |
void | callForPose (int id) |
bool | change_robot_number (int client_fd) |
void | change_robot_number_local (int number) |
vector< cv::Mat > | crt_depth_images (rbtnum) |
vector< cv::Mat > | crt_rgb_images (rbtnum) |
void | depthImageCallback (const sensor_msgs::ImageConstPtr &msg, const std::string &rbtID) |
bool | getDepth (int client_fd) |
bool | getPose (int client_fd) |
bool | getRGBD (int client_fd) |
void | goToPose (float x0, float y0, float qx0, float qy0, float qz0, float qw0, float x1, float y1, float qx1, float qy1, float qz1, float qw1, float x2, float y2, float qx2, float qy2, float qz2, float qw2) |
void | infoCallback (const sensor_msgs::CameraInfoConstPtr &msg) |
string | int2str (int n) |
int | main (int argc, char **argv) |
bool | move_to_views (int client_fd) |
int | recvData (const int client_fd, char buf[], int len) |
void | rgbImageCallback (const sensor_msgs::ImageConstPtr &msg, const std::string &rbtID) |
bool | scanSurroundings (int client_fd) |
bool | sendData (const int client_fd, const char *ch, const int len) |
int | sendTotalData (const int client_fd, const char *buf, const int len) |
void | setForPose (int id, float x, float y, float z, float qx, float qy, float qz, float qw) |
bool | setPath (int client_fd) |
bool | setPose (int client_fd) |
bool | setTaskPositions (int client_fd) |
cv::Mat | shortImg (480, 640, CV_16UC1) |
int | str2int (string s) |
vector< image_transport::Subscriber > | subsColor (rbtnum) |
vector< image_transport::Subscriber > | subsDepth (rbtnum) |
void * | thread (void *ptr) |
Variables | |
const float | camera_cx = 320.500000 |
const float | camera_cy = 240.500000 |
const float | camera_factor = 1000 |
const float | camera_fx = 554.382713 |
const float | camera_fy = 554.382713 |
float | camera_height = 1.1 |
int | client_fd |
bool | depth_ready = false |
ros::ServiceClient | gclient |
image_transport::ImageTransport * | it |
const int | MAXRECV = 10240 |
struct sockaddr_in | my_addr |
ofstream | ofs_off |
vector< vector< PositionInGazebo > > | path_poses |
float | pose [7] |
bool | pose_ready = false |
float | rbt_v = 1.0/times - 0.01 |
int | rbtnum = 3 |
struct sockaddr_in | remote_addr |
bool | rgb_ready = false |
cv::Mat | rgbImg |
ros::ServiceClient | sclient |
int | sin_size |
int | sockfd |
vector< PositionInGazebo > | task_poses |
const int | times = 1.0 |
#define BACKLOG 10 |
Definition at line 38 of file vscan_server.cpp.
#define PI 3.1415926 |
Definition at line 31 of file vscan_server.cpp.
#define SERVPORT 3333 |
Definition at line 33 of file vscan_server.cpp.
void callForPose | ( | int | id | ) |
Definition at line 149 of file vscan_server.cpp.
bool change_robot_number | ( | int | client_fd | ) |
Definition at line 990 of file vscan_server.cpp.
void change_robot_number_local | ( | int | number | ) |
Definition at line 948 of file vscan_server.cpp.
vector<cv::Mat> crt_depth_images | ( | rbtnum | ) |
vector<cv::Mat> crt_rgb_images | ( | rbtnum | ) |
void depthImageCallback | ( | const sensor_msgs::ImageConstPtr & | msg, |
const std::string & | rbtID | ||
) |
Definition at line 117 of file vscan_server.cpp.
bool getDepth | ( | int | client_fd | ) |
Definition at line 356 of file vscan_server.cpp.
bool getPose | ( | int | client_fd | ) |
Definition at line 365 of file vscan_server.cpp.
bool getRGBD | ( | int | client_fd | ) |
Definition at line 278 of file vscan_server.cpp.
void goToPose | ( | float | x0, |
float | y0, | ||
float | qx0, | ||
float | qy0, | ||
float | qz0, | ||
float | qw0, | ||
float | x1, | ||
float | y1, | ||
float | qx1, | ||
float | qy1, | ||
float | qz1, | ||
float | qw1, | ||
float | x2, | ||
float | y2, | ||
float | qx2, | ||
float | qy2, | ||
float | qz2, | ||
float | qw2 | ||
) |
Definition at line 406 of file vscan_server.cpp.
void infoCallback | ( | const sensor_msgs::CameraInfoConstPtr & | msg | ) |
Definition at line 200 of file vscan_server.cpp.
string int2str | ( | int | n | ) |
Definition at line 76 of file vscan_server.cpp.
int main | ( | int | argc, |
char ** | argv | ||
) |
Definition at line 1096 of file vscan_server.cpp.
bool move_to_views | ( | int | client_fd | ) |
Definition at line 508 of file vscan_server.cpp.
int recvData | ( | const int | client_fd, |
char | buf[], | ||
int | len | ||
) |
Definition at line 208 of file vscan_server.cpp.
void rgbImageCallback | ( | const sensor_msgs::ImageConstPtr & | msg, |
const std::string & | rbtID | ||
) |
Definition at line 94 of file vscan_server.cpp.
bool scanSurroundings | ( | int | client_fd | ) |
Definition at line 885 of file vscan_server.cpp.
bool sendData | ( | const int | client_fd, |
const char * | ch, | ||
const int | len | ||
) |
Definition at line 247 of file vscan_server.cpp.
int sendTotalData | ( | const int | client_fd, |
const char * | buf, | ||
const int | len | ||
) |
Definition at line 261 of file vscan_server.cpp.
void setForPose | ( | int | id, |
float | x, | ||
float | y, | ||
float | z, | ||
float | qx, | ||
float | qy, | ||
float | qz, | ||
float | qw | ||
) |
Definition at line 173 of file vscan_server.cpp.
bool setPath | ( | int | client_fd | ) |
Definition at line 605 of file vscan_server.cpp.
bool setPose | ( | int | client_fd | ) |
Definition at line 559 of file vscan_server.cpp.
bool setTaskPositions | ( | int | client_fd | ) |
Definition at line 922 of file vscan_server.cpp.
cv::Mat shortImg | ( | 480 | , |
640 | , | ||
CV_16UC1 | |||
) |
int str2int | ( | string | s | ) |
Definition at line 85 of file vscan_server.cpp.
vector<image_transport::Subscriber> subsColor | ( | rbtnum | ) |
vector<image_transport::Subscriber> subsDepth | ( | rbtnum | ) |
void* thread | ( | void * | ptr | ) |
Definition at line 1005 of file vscan_server.cpp.
const float camera_cx = 320.500000 |
Definition at line 63 of file vscan_server.cpp.
const float camera_cy = 240.500000 |
Definition at line 64 of file vscan_server.cpp.
const float camera_factor = 1000 |
Definition at line 62 of file vscan_server.cpp.
const float camera_fx = 554.382713 |
Definition at line 65 of file vscan_server.cpp.
const float camera_fy = 554.382713 |
Definition at line 66 of file vscan_server.cpp.
float camera_height = 1.1 |
Definition at line 41 of file vscan_server.cpp.
int client_fd |
Definition at line 34 of file vscan_server.cpp.
bool depth_ready = false |
Definition at line 46 of file vscan_server.cpp.
ros::ServiceClient gclient |
Definition at line 57 of file vscan_server.cpp.
image_transport::ImageTransport* it |
Definition at line 49 of file vscan_server.cpp.
const int MAXRECV = 10240 |
Definition at line 37 of file vscan_server.cpp.
struct sockaddr_in my_addr |
Definition at line 35 of file vscan_server.cpp.
ofstream ofs_off |
Definition at line 74 of file vscan_server.cpp.
vector< vector< PositionInGazebo > > path_poses |
Definition at line 601 of file vscan_server.cpp.
float pose[7] |
Definition at line 59 of file vscan_server.cpp.
bool pose_ready = false |
Definition at line 60 of file vscan_server.cpp.
float rbt_v = 1.0/times - 0.01 |
Definition at line 69 of file vscan_server.cpp.
int rbtnum = 3 |
Definition at line 40 of file vscan_server.cpp.
struct sockaddr_in remote_addr |
Definition at line 36 of file vscan_server.cpp.
bool rgb_ready = false |
Definition at line 45 of file vscan_server.cpp.
cv::Mat rgbImg |
Definition at line 43 of file vscan_server.cpp.
ros::ServiceClient sclient |
Definition at line 58 of file vscan_server.cpp.
int sin_size |
Definition at line 34 of file vscan_server.cpp.
int sockfd |
Definition at line 34 of file vscan_server.cpp.
vector< PositionInGazebo > task_poses |
Definition at line 602 of file vscan_server.cpp.
const int times = 1.0 |
Definition at line 68 of file vscan_server.cpp.