Macros | Functions | Variables
complete_test.cpp File Reference
#include <geometry_msgs/Twist.h>
#include <geometry_msgs/WrenchStamped.h>
#include <sensor_msgs/Illuminance.h>
#include <sensor_msgs/Image.h>
#include <sensor_msgs/Imu.h>
#include <sensor_msgs/MagneticField.h>
#include <sensor_msgs/NavSatFix.h>
#include <sensor_msgs/Range.h>
#include <signal.h>
#include <std_msgs/Float32MultiArray.h>
#include <std_msgs/Float64.h>
#include <std_msgs/Float64MultiArray.h>
#include <std_msgs/String.h>
#include <std_msgs/UInt16.h>
#include <std_msgs/UInt8MultiArray.h>
#include <webots_ros/BoolStamped.h>
#include <webots_ros/Float64Stamped.h>
#include <webots_ros/Int32Stamped.h>
#include <webots_ros/Int8Stamped.h>
#include <webots_ros/RadarTarget.h>
#include <webots_ros/RecognitionObject.h>
#include <webots_ros/StringStamped.h>
#include <cstdlib>
#include "ros/ros.h"
#include <webots_ros/get_bool.h>
#include <webots_ros/get_float.h>
#include <webots_ros/get_int.h>
#include <webots_ros/get_string.h>
#include <webots_ros/get_uint64.h>
#include <webots_ros/set_bool.h>
#include <webots_ros/set_float.h>
#include <webots_ros/set_float_array.h>
#include <webots_ros/set_int.h>
#include <webots_ros/set_string.h>
#include <webots_ros/camera_get_focus_info.h>
#include <webots_ros/camera_get_info.h>
#include <webots_ros/camera_get_zoom_info.h>
#include <webots_ros/display_draw_line.h>
#include <webots_ros/display_draw_oval.h>
#include <webots_ros/display_draw_pixel.h>
#include <webots_ros/display_draw_polygon.h>
#include <webots_ros/display_draw_rectangle.h>
#include <webots_ros/display_draw_text.h>
#include <webots_ros/display_get_info.h>
#include <webots_ros/display_image_copy.h>
#include <webots_ros/display_image_delete.h>
#include <webots_ros/display_image_load.h>
#include <webots_ros/display_image_new.h>
#include <webots_ros/display_image_paste.h>
#include <webots_ros/display_image_save.h>
#include <webots_ros/display_set_font.h>
#include <webots_ros/field_get_bool.h>
#include <webots_ros/field_get_color.h>
#include <webots_ros/field_get_count.h>
#include <webots_ros/field_get_float.h>
#include <webots_ros/field_get_int32.h>
#include <webots_ros/field_get_node.h>
#include <webots_ros/field_get_rotation.h>
#include <webots_ros/field_get_string.h>
#include <webots_ros/field_get_type.h>
#include <webots_ros/field_get_type_name.h>
#include <webots_ros/field_get_vec2f.h>
#include <webots_ros/field_get_vec3f.h>
#include <webots_ros/field_import_node.h>
#include <webots_ros/field_remove.h>
#include <webots_ros/field_set_bool.h>
#include <webots_ros/field_set_color.h>
#include <webots_ros/field_set_float.h>
#include <webots_ros/field_set_int32.h>
#include <webots_ros/field_set_rotation.h>
#include <webots_ros/field_set_string.h>
#include <webots_ros/field_set_vec2f.h>
#include <webots_ros/field_set_vec3f.h>
#include <webots_ros/lidar_get_frequency_info.h>
#include <webots_ros/lidar_get_info.h>
#include <webots_ros/motor_set_control_pid.h>
#include <webots_ros/node_get_center_of_mass.h>
#include <webots_ros/node_get_contact_point.h>
#include <webots_ros/node_get_field.h>
#include <webots_ros/node_get_id.h>
#include <webots_ros/node_get_name.h>
#include <webots_ros/node_get_number_of_contact_points.h>
#include <webots_ros/node_get_orientation.h>
#include <webots_ros/node_get_parent_node.h>
#include <webots_ros/node_get_position.h>
#include <webots_ros/node_get_static_balance.h>
#include <webots_ros/node_get_status.h>
#include <webots_ros/node_get_type.h>
#include <webots_ros/node_get_velocity.h>
#include <webots_ros/node_remove.h>
#include <webots_ros/node_reset_functions.h>
#include <webots_ros/node_set_velocity.h>
#include <webots_ros/node_set_visibility.h>
#include <webots_ros/pen_set_ink_color.h>
#include <webots_ros/range_finder_get_info.h>
#include <webots_ros/receiver_get_emitter_direction.h>
#include <webots_ros/robot_get_device_list.h>
#include <webots_ros/robot_set_mode.h>
#include <webots_ros/robot_wait_for_user_input_event.h>
#include <webots_ros/save_image.h>
#include <webots_ros/speaker_play_sound.h>
#include <webots_ros/speaker_speak.h>
#include <webots_ros/supervisor_get_from_def.h>
#include <webots_ros/supervisor_get_from_id.h>
#include <webots_ros/supervisor_movie_start_recording.h>
#include <webots_ros/supervisor_set_label.h>
#include <webots_ros/supervisor_virtual_reality_headset_get_orientation.h>
#include <webots_ros/supervisor_virtual_reality_headset_get_position.h>

Go to the source code of this file.

Macros

#define TIME_STEP   32
 

Functions

void accelerometerCallback (const sensor_msgs::Imu::ConstPtr &values)
 
void battery_sensorCallback (const webots_ros::Float64Stamped::ConstPtr &value)
 
void cameraCallback (const sensor_msgs::Image::ConstPtr &values)
 
void compassCallback (const sensor_msgs::MagneticField::ConstPtr &values)
 
void connectorCallback (const webots_ros::Int8Stamped::ConstPtr &value)
 
void distance_sensorCallback (const sensor_msgs::Range::ConstPtr &value)
 
void GPSCallback (const sensor_msgs::NavSatFix::ConstPtr &values)
 
void GPSSpeedCallback (const webots_ros::Float64Stamped::ConstPtr &value)
 
void gyroCallback (const sensor_msgs::Imu::ConstPtr &values)
 
void inertialUnitCallback (const sensor_msgs::Imu::ConstPtr &values)
 
void joystickCallback (const webots_ros::Int8Stamped::ConstPtr &value)
 
void keyboardCallback (const webots_ros::Int32Stamped::ConstPtr &value)
 
void lidarCallback (const sensor_msgs::Image::ConstPtr &image)
 
void lightSensorCallback (const sensor_msgs::Illuminance::ConstPtr &value)
 
int main (int argc, char **argv)
 
void modelNameCallback (const std_msgs::String::ConstPtr &name)
 
void motorSensorCallback (const std_msgs::Float64::ConstPtr &value)
 
void positionSensorCallback (const webots_ros::Float64Stamped::ConstPtr &value)
 
void quit (int sig)
 
void radarTargetsCallback (const webots_ros::RadarTarget::ConstPtr &target)
 
void radarTargetsNumberCallback (const webots_ros::Int8Stamped::ConstPtr &value)
 
void rangeFinderCallback (const sensor_msgs::Image::ConstPtr &image)
 
void receiverCallback (const webots_ros::StringStamped::ConstPtr &value)
 
void touchSensor3DCallback (const geometry_msgs::WrenchStamped::ConstPtr &values)
 
void touchSensorBumperCallback (const webots_ros::BoolStamped::ConstPtr &value)
 
void touchSensorCallback (const webots_ros::Float64Stamped::ConstPtr &value)
 

Variables

double accelerometerValues [3] = {0, 0, 0}
 
double compassValues [3] = {0, 0, 0}
 
int connectorPresence = 0
 
double GPSValues [3] = {0, 0, 0}
 
double GyroValues [3] = {0, 0, 0}
 
vector< unsigned char > imageColor
 
vector< float > imageRangeFinder
 
double inertialUnitValues [4] = {0, 0, 0, 0}
 
static int model_count
 
static vector< string > model_list
 
ros::ServiceClient time_step_client
 
webots_ros::set_int time_step_srv
 
double touchSensorValues [3] = {0, 0, 0}
 

Macro Definition Documentation

#define TIME_STEP   32

Definition at line 126 of file complete_test.cpp.

Function Documentation

void accelerometerCallback ( const sensor_msgs::Imu::ConstPtr &  values)

Definition at line 197 of file complete_test.cpp.

void battery_sensorCallback ( const webots_ros::Float64Stamped::ConstPtr &  value)

Definition at line 206 of file complete_test.cpp.

void cameraCallback ( const sensor_msgs::Image::ConstPtr &  values)

Definition at line 151 of file complete_test.cpp.

void compassCallback ( const sensor_msgs::MagneticField::ConstPtr &  values)

Definition at line 210 of file complete_test.cpp.

void connectorCallback ( const webots_ros::Int8Stamped::ConstPtr &  value)

Definition at line 191 of file complete_test.cpp.

void distance_sensorCallback ( const sensor_msgs::Range::ConstPtr &  value)

Definition at line 219 of file complete_test.cpp.

void GPSCallback ( const sensor_msgs::NavSatFix::ConstPtr &  values)

Definition at line 223 of file complete_test.cpp.

void GPSSpeedCallback ( const webots_ros::Float64Stamped::ConstPtr &  value)

Definition at line 232 of file complete_test.cpp.

void gyroCallback ( const sensor_msgs::Imu::ConstPtr &  values)

Definition at line 236 of file complete_test.cpp.

void inertialUnitCallback ( const sensor_msgs::Imu::ConstPtr &  values)

Definition at line 245 of file complete_test.cpp.

void joystickCallback ( const webots_ros::Int8Stamped::ConstPtr &  value)

Definition at line 160 of file complete_test.cpp.

void keyboardCallback ( const webots_ros::Int32Stamped::ConstPtr &  value)

Definition at line 164 of file complete_test.cpp.

void lidarCallback ( const sensor_msgs::Image::ConstPtr &  image)

Definition at line 188 of file complete_test.cpp.

void lightSensorCallback ( const sensor_msgs::Illuminance::ConstPtr &  value)

Definition at line 256 of file complete_test.cpp.

int main ( int  argc,
char **  argv 
)

Definition at line 298 of file complete_test.cpp.

void modelNameCallback ( const std_msgs::String::ConstPtr &  name)

Definition at line 145 of file complete_test.cpp.

void motorSensorCallback ( const std_msgs::Float64::ConstPtr &  value)

Definition at line 260 of file complete_test.cpp.

void positionSensorCallback ( const webots_ros::Float64Stamped::ConstPtr &  value)

Definition at line 264 of file complete_test.cpp.

void quit ( int  sig)

Definition at line 290 of file complete_test.cpp.

void radarTargetsCallback ( const webots_ros::RadarTarget::ConstPtr &  target)

Definition at line 168 of file complete_test.cpp.

void radarTargetsNumberCallback ( const webots_ros::Int8Stamped::ConstPtr &  value)

Definition at line 174 of file complete_test.cpp.

void rangeFinderCallback ( const sensor_msgs::Image::ConstPtr &  image)

Definition at line 179 of file complete_test.cpp.

void receiverCallback ( const webots_ros::StringStamped::ConstPtr &  value)

Definition at line 285 of file complete_test.cpp.

void touchSensor3DCallback ( const geometry_msgs::WrenchStamped::ConstPtr &  values)

Definition at line 276 of file complete_test.cpp.

void touchSensorBumperCallback ( const webots_ros::BoolStamped::ConstPtr &  value)

Definition at line 272 of file complete_test.cpp.

void touchSensorCallback ( const webots_ros::Float64Stamped::ConstPtr &  value)

Definition at line 268 of file complete_test.cpp.

Variable Documentation

double accelerometerValues[3] = {0, 0, 0}

Definition at line 135 of file complete_test.cpp.

double compassValues[3] = {0, 0, 0}

Definition at line 136 of file complete_test.cpp.

int connectorPresence = 0

Definition at line 134 of file complete_test.cpp.

double GPSValues[3] = {0, 0, 0}

Definition at line 137 of file complete_test.cpp.

double GyroValues[3] = {0, 0, 0}

Definition at line 138 of file complete_test.cpp.

vector<unsigned char> imageColor

Definition at line 132 of file complete_test.cpp.

vector<float> imageRangeFinder

Definition at line 133 of file complete_test.cpp.

double inertialUnitValues[4] = {0, 0, 0, 0}

Definition at line 139 of file complete_test.cpp.

int model_count
static

Definition at line 130 of file complete_test.cpp.

vector<string> model_list
static

Definition at line 131 of file complete_test.cpp.

ros::ServiceClient time_step_client

Definition at line 142 of file complete_test.cpp.

webots_ros::set_int time_step_srv

Definition at line 143 of file complete_test.cpp.

double touchSensorValues[3] = {0, 0, 0}

Definition at line 140 of file complete_test.cpp.



webots_ros
Author(s):
autogenerated on Mon Jul 8 2019 03:19:27