21 #include <sensor_msgs/Image.h>    22 #include <sensor_msgs/Imu.h>    23 #include <sensor_msgs/LaserScan.h>    24 #include <sensor_msgs/NavSatFix.h>    26 #include <std_msgs/String.h>    30 #include <webots_ros/set_float.h>    31 #include <webots_ros/set_int.h>    36 #define OBSTACLE_THRESHOLD 0.1    37 #define DECREASE_FACTOR 0.9    38 #define BACK_SLOWDOWN 0.9    50 static const char *
motorNames[
NMOTORS] = {
"front_left_wheel", 
"front_right_wheel", 
"back_left_wheel", 
"back_right_wheel"};
    63 double gaussian(
double x, 
double mu, 
double sigma) {
    64   return (1.0 / (sigma * sqrt(2.0 * M_PI))) * exp(-((x - mu) * (x - mu)) / (2 * sigma * sigma));
    69   double leftObstacle = 0.0, rightObstacle = 0.0, obstacle = 0.0;
    82   obstacle = leftObstacle + rightObstacle;
    87     speeds[0] = speedFactor * leftObstacle;
    88     speeds[1] = speedFactor * rightObstacle;
    98   for (
int i = 0; i < 
NMOTORS; ++i) {
   100     webots_ros::set_float set_velocity_srv;
   101     set_velocity_client = n->
serviceClient<webots_ros::set_float>(std::string(
"pioneer3at/") + std::string(
motorNames[i]) +
   102                                                                   std::string(
"/set_velocity"));
   103     set_velocity_srv.request.value = speeds[i];
   104     set_velocity_client.
call(set_velocity_srv);
   120 void GPSCallback(
const sensor_msgs::NavSatFix::ConstPtr &values) {
   136   int scanSize = scan->ranges.size();
   138   for (
int i = 0; i < scanSize; ++i)
   163   ROS_INFO(
"User stopped the 'pioneer3at' node.");
   170 int main(
int argc, 
char **argv) {
   176   signal(SIGINT, 
quit);
   187   timeStepClient = n->
serviceClient<webots_ros::set_int>(
"pioneer3at/robot/time_step");
   194     int wantedController = 0;
   195     std::cout << 
"Choose the # of the controller you want to use:\n";
   196     std::cin >> wantedController;
   200       ROS_ERROR(
"Invalid number for controller choice.");
   204   ROS_INFO(
"Using controller: '%s'", controllerName.c_str());
   209   for (
int i = 0; i < 
NMOTORS; ++i) {
   212     webots_ros::set_float set_position_srv;
   213     set_position_client = n->
serviceClient<webots_ros::set_float>(std::string(
"pioneer3at/") + std::string(
motorNames[i]) +
   214                                                                   std::string(
"/set_position"));
   216     set_position_srv.request.value = INFINITY;
   217     if (set_position_client.
call(set_position_srv) && set_position_srv.response.success)
   224     webots_ros::set_float set_velocity_srv;
   225     set_velocity_client = n->
serviceClient<webots_ros::set_float>(std::string(
"pioneer3at/") + std::string(
motorNames[i]) +
   226                                                                   std::string(
"/set_velocity"));
   228     set_velocity_srv.request.value = 0.0;
   229     if (set_velocity_client.
call(set_velocity_srv) && set_velocity_srv.response.success == 1)
   237   webots_ros::set_int lidar_srv;
   240   set_lidar_client = n->
serviceClient<webots_ros::set_int>(
"pioneer3at/Sick_LMS_291/enable");
   242   if (set_lidar_client.
call(lidar_srv) && lidar_srv.response.success) {
   245     ROS_INFO(
"Topic for lidar initialized.");
   248     ROS_INFO(
"Topic for lidar scan connected.");
   250     if (!lidar_srv.response.success)
   251       ROS_ERROR(
"Sampling period is not valid.");
   258   webots_ros::set_int GPS_srv;
   260   set_GPS_client = n->
serviceClient<webots_ros::set_int>(
"pioneer3at/gps/enable");
   261   GPS_srv.request.value = 32;
   262   if (set_GPS_client.
call(GPS_srv) && GPS_srv.response.success) {
   268     if (!GPS_srv.response.success)
   269       ROS_ERROR(
"Sampling period is not valid.");
   276   webots_ros::set_int inertial_unit_srv;
   278   set_inertial_unit_client = n->
serviceClient<webots_ros::set_int>(
"pioneer3at/inertial_unit/enable");
   279   inertial_unit_srv.request.value = 32;
   280   if (set_inertial_unit_client.
call(inertial_unit_srv) && inertial_unit_srv.response.success) {
   286     if (!inertial_unit_srv.response.success)
   287       ROS_ERROR(
"Sampling period is not valid.");
   288     ROS_ERROR(
"Failed to enable inertial unit.");
   294   webots_ros::set_int accelerometer_srv;
   296   set_accelerometer_client = n->
serviceClient<webots_ros::set_int>(
"pioneer3at/accelerometer/enable");
   297   accelerometer_srv.request.value = 32;
   298   set_accelerometer_client.
call(accelerometer_srv);
   301   webots_ros::set_int camera_srv;
   303   set_camera_client = n->
serviceClient<webots_ros::set_int>(
"pioneer3at/camera/enable");
   304   camera_srv.request.value = 64;
   305   set_camera_client.
call(camera_srv);
   308   webots_ros::set_int gyro_srv;
   310   set_gyro_client = n->
serviceClient<webots_ros::set_int>(
"pioneer3at/gyro/enable");
   311   gyro_srv.request.value = 32;
   312   set_gyro_client.
call(gyro_srv);
   314   ROS_INFO(
"You can now start the creation of the map using 'rosrun gmapping slam_gmapping "   315            "scan:=/pioneer3at/Sick_LMS_291/laser_scan/layer0 _xmax:=30 _xmin:=-30 _ymax:=30 _ymin:=-30 _delta:=0.2'.");
   316   ROS_INFO(
"You can now visualize the sensors output in rqt using 'rqt'.");
   321       ROS_ERROR(
"Failed to call service time_step for next step.");
 void GPSCallback(const sensor_msgs::NavSatFix::ConstPtr &values)
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
static int controllerCount
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
static int halfResolution
static double rangeThreshold
void inertialUnitCallback(const sensor_msgs::Imu::ConstPtr &values)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
static std::vector< float > lidarValues
void lidarCallback(const sensor_msgs::LaserScan::ConstPtr &scan)
bool call(MReq &req, MRes &res)
ros::ServiceClient timeStepClient
static std::string controllerName
static int lms291Resolution
webots_ros::set_int timeStepSrv
void broadcastTransform()
#define OBSTACLE_THRESHOLD
uint32_t getNumPublishers() const 
int main(int argc, char **argv)
void controllerNameCallback(const std_msgs::String::ConstPtr &name)
static bool areBraitenbergCoefficientsinitialized
double gaussian(double x, double mu, double sigma)
Quaternion inverse() const 
static std::vector< std::string > controllerList
static const char * motorNames[NMOTORS]
static double GPSValues[3]
ROSCPP_DECL void shutdown()
ROSCPP_DECL void spinOnce()
static double inertialUnitValues[4]
static std::vector< double > braitenbergCoefficients