diff --git a/app/simpleVelocityNavigationExamples/scripts/simpleVelocityNavigationExample1.xml b/app/simpleVelocityNavigationExamples/scripts/simpleVelocityNavigationExample1.xml
index 143fb11a..8d866c84 100644
--- a/app/simpleVelocityNavigationExamples/scripts/simpleVelocityNavigationExample1.xml
+++ b/app/simpleVelocityNavigationExamples/scripts/simpleVelocityNavigationExample1.xml
@@ -36,13 +36,13 @@
yarpdev
- --device Rangefinder2DWrapper --subdevice fakeLaser --period 10 --name /ikart/laser:o --test use_mapfile --map_file C:\\software\\maps\\map_test.map
+ --device Rangefinder2DWrapper --subdevice fakeLaser --period 10 --name /robot_2wheels/laser:o --test use_mapfile --map_file C:\\software\\maps\\map_test.map
console
yarpdev
- --device navigation2DServer --subdevice simpleVelocityNavigation --context simpleVelocityNavigationExamples --from robotGoto_robot_2wheels.ini
+ --device navigation2DServer --subdevice simpleVelocityNavigation --context simpleVelocityNavigationExamples --from simpleVelocityControl.ini
console
diff --git a/app/simpleVelocityNavigationExamples/scripts/simpleVelocityNavigationExample2.xml b/app/simpleVelocityNavigationExamples/scripts/simpleVelocityNavigationExample2.xml
new file mode 100644
index 00000000..83a7cb2e
--- /dev/null
+++ b/app/simpleVelocityNavigationExamples/scripts/simpleVelocityNavigationExample2.xml
@@ -0,0 +1,61 @@
+
+simpleVelocityNavigation (with Laser) EXAMPLE2
+
+
+
+
+
+ yarpdev
+ --device transformServer --ROS "(enable_ros_publisher 0)" "(enable_ros_subscriber 0)"
+ console
+
+
+
+ yarpdev
+ --device fakeMotionControl --name /robot_2wheels/mobile_base --GENERAL::Joints 2
+ console
+
+
+
+ baseControl
+ --context baseControl_SIM --from robot_2wheels.ini --skip_robot_interface_check
+ console
+
+
+
+ yarpdev
+ --device localization2DServer --subdevice odomLocalizer --context simpleVelocityNavigationExamples --from localizationServer.ini
+ console
+
+
+
+ yarpdev
+ --device map2DServer --mapCollectionContext mapsExample
+ console
+
+
+
+ yarpdev
+ --device Rangefinder2DWrapper --subdevice fakeLaser --period 10 --name /robot_2wheels/laser:o --test use_mapfile --map_file C:\\software\\maps\\map_test.map
+ console
+
+
+
+ yarpdev
+ --device navigation2DServer --subdevice simpleVelocityNavigationWithLaser --context simpleVelocityNavigationExamples --from simpleVelocityControl.ini
+ console
+
+
+
+ /simpleVelocityNavigation/control:o
+ /baseControl/control:i
+ udp
+
+
+
+ /baseControl/odometry:o
+ /fakeLaser/location:i
+ tcp
+
+
+
diff --git a/src/common/CMakeLists.txt b/src/common/CMakeLists.txt
index db6477e7..fc304ae5 100644
--- a/src/common/CMakeLists.txt
+++ b/src/common/CMakeLists.txt
@@ -8,12 +8,14 @@ set(PROJECT_NAME navigation_lib)
set(LIBRARY_TARGET_NAME ${PROJECT_NAME})
set(${LIBRARY_TARGET_NAME}_SRC
- movable_localization_device/movable_localization_device.cpp)
+ movable_localization_device/movable_localization_device.cpp
+ obstacle_detection_avoidance/obstacles.cpp)
set(${LIBRARY_TARGET_NAME}_HDR
movable_localization_device/movable_localization_device.h
- include/navigation_defines.h)
+ include/navigation_defines.h
+ obstacle_detection_avoidance/obstacles.h)
add_library(${LIBRARY_TARGET_NAME} ${${LIBRARY_TARGET_NAME}_SRC} ${${LIBRARY_TARGET_NAME}_HDR})
add_library(${PROJECT_NAME}::${LIBRARY_TARGET_NAME} ALIAS ${LIBRARY_TARGET_NAME})
@@ -22,6 +24,7 @@ set_target_properties(${LIBRARY_TARGET_NAME} PROPERTIES VERSION 0}
PUBLIC_HEADER "${${LIBRARY_TARGET_NAME}_HDR}")
target_include_directories(${LIBRARY_TARGET_NAME} PUBLIC "$"
+ "$"
"$"
"$/${CMAKE_INSTALL_INCLUDEDIR}>")
diff --git a/src/navigationDevices/robotGotoDevice/obstacles.cpp b/src/common/obstacle_detection_avoidance/obstacles.cpp
similarity index 100%
rename from src/navigationDevices/robotGotoDevice/obstacles.cpp
rename to src/common/obstacle_detection_avoidance/obstacles.cpp
diff --git a/src/navigationDevices/robotGotoDevice/obstacles.h b/src/common/obstacle_detection_avoidance/obstacles.h
similarity index 100%
rename from src/navigationDevices/robotGotoDevice/obstacles.h
rename to src/common/obstacle_detection_avoidance/obstacles.h
diff --git a/src/navigationDevices/CMakeLists.txt b/src/navigationDevices/CMakeLists.txt
index 073fd069..9c513ff5 100644
--- a/src/navigationDevices/CMakeLists.txt
+++ b/src/navigationDevices/CMakeLists.txt
@@ -9,3 +9,4 @@ add_subdirectory(robotGotoDevice)
add_subdirectory(robotPathPlannerDevice)
add_subdirectory(rosNavigator)
add_subdirectory(simpleVelocityNavigation)
+add_subdirectory(simpleVelocityNavigationWithLaser)
\ No newline at end of file
diff --git a/src/navigationDevices/robotGotoDevice/CMakeLists.txt b/src/navigationDevices/robotGotoDevice/CMakeLists.txt
index d476bc52..048c41b4 100644
--- a/src/navigationDevices/robotGotoDevice/CMakeLists.txt
+++ b/src/navigationDevices/robotGotoDevice/CMakeLists.txt
@@ -13,13 +13,14 @@ yarp_prepare_plugin(robotGotoDev
set(CMAKE_INCLUDE_CURRENT_DIR ON)
-yarp_add_plugin(robotGotoDev robotGotoDev.h robotGotoDev.cpp robotGotoCtrl.h robotGotoCtrl.cpp obstacles.h obstacles.cpp )
+yarp_add_plugin(robotGotoDev robotGotoDev.h robotGotoDev.cpp robotGotoCtrl.h robotGotoCtrl.cpp)
target_link_libraries(robotGotoDev YARP::YARP_os
YARP::YARP_sig
YARP::YARP_dev
YARP::YARP_math
- YARP::YARP_rosmsg)
+ YARP::YARP_rosmsg
+ navigation_lib)
yarp_install(TARGETS robotGotoDev
diff --git a/src/navigationDevices/robotGotoDevice/robotGotoCtrl.h b/src/navigationDevices/robotGotoDevice/robotGotoCtrl.h
index 81bfc278..148d7b28 100644
--- a/src/navigationDevices/robotGotoDevice/robotGotoCtrl.h
+++ b/src/navigationDevices/robotGotoDevice/robotGotoCtrl.h
@@ -45,7 +45,7 @@
#include
#include
#include
-#include "obstacles.h"
+#include
using namespace std;
using namespace yarp::os;
diff --git a/src/navigationDevices/simpleVelocityNavigation/simpleVelocityNavigation.cpp b/src/navigationDevices/simpleVelocityNavigation/simpleVelocityNavigation.cpp
index 049ad9c4..3fe8920f 100644
--- a/src/navigationDevices/simpleVelocityNavigation/simpleVelocityNavigation.cpp
+++ b/src/navigationDevices/simpleVelocityNavigation/simpleVelocityNavigation.cpp
@@ -1,19 +1,9 @@
/*
- * Copyright (C)2018 ICub Facility - Istituto Italiano di Tecnologia
- * Author: Marco Randazzo
- * email: marco.randazzo@iit.it
- * website: www.robotcub.org
- * Permission is granted to copy, distribute, and/or modify this program
- * under the terms of the GNU General Public License, version 2 or any
- * later version published by the Free Software Foundation.
- *
- * A copy of the license can be found at
- * http://www.robotcub.org/icub/license/gpl.txt
- *
- * This program is distributed in the hope that it will be useful, but
- * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General
- * Public License for more details
+• Copyright (C) 2019 Istituto Italiano di Tecnologia (IIT)
+• All rights reserved.
+•
+• This software may be modified and distributed under the terms of the
+• GPL-2+ license. See the accompanying LICENSE file for details.
*/
#include
@@ -134,19 +124,19 @@ void simpleVelocityNavigation::send_command(control_type control_data)
bool simpleVelocityNavigation::gotoTargetByAbsoluteLocation(Map2DLocation loc)
{
- yError() << "gotoTargetByAbsoluteLocation() Not implemented by simpleVelocityNavigation";
+ yError() << "gotoTargetByAbsoluteLocation() Not implemented by " << m_localName;
return NOT_IMPLEMENTED;
}
bool simpleVelocityNavigation::gotoTargetByRelativeLocation(double x, double y)
{
- yError() << "gotoTargetByRelativeLocation() Not implemented by simpleVelocityNavigation";
+ yError() << "gotoTargetByRelativeLocation() Not implemented by " << m_localName;
return NOT_IMPLEMENTED;
}
bool simpleVelocityNavigation::gotoTargetByRelativeLocation(double x, double y, double theta)
{
- yError() << "gotoTargetByRelativeLocation() Not implemented by simpleVelocityNavigation";
+ yError() << "gotoTargetByRelativeLocation() Not implemented by " << m_localName;
return NOT_IMPLEMENTED;
}
@@ -168,54 +158,54 @@ bool simpleVelocityNavigation::getNavigationStatus(yarp::dev::NavigationStatusEn
bool simpleVelocityNavigation::stopNavigation()
{
- yError() << "stopNavigation() Not implemented by simpleVelocityNavigation";
+ yError() << "stopNavigation() Not implemented by " << m_localName;
return NOT_IMPLEMENTED;
}
bool simpleVelocityNavigation::getAbsoluteLocationOfCurrentTarget(Map2DLocation& target)
{
- yError() << "getAbsoluteLocationOfCurrentTarget() Not implemented by simpleVelocityNavigation";
+ yError() << "getAbsoluteLocationOfCurrentTarget() Not implemented by " << m_localName;
return NOT_IMPLEMENTED;
}
bool simpleVelocityNavigation::getRelativeLocationOfCurrentTarget(double& x, double& y, double& theta)
{
- yError() << "getRelativeLocationOfCurrentTarget() Not implemented by simpleVelocityNavigation";
+ yError() << "getRelativeLocationOfCurrentTarget() Not implemented by " << m_localName;
return NOT_IMPLEMENTED;
}
bool simpleVelocityNavigation::getAllNavigationWaypoints(Map2DPath& waypoints)
{
- yError() << "getAllNavigationWaypoints() Not implemented by simpleVelocityNavigation";
+ yError() << "getAllNavigationWaypoints() Not implemented by " << m_localName;
return NOT_IMPLEMENTED;
}
bool simpleVelocityNavigation::getCurrentNavigationWaypoint(Map2DLocation& curr_waypoint)
{
- yError() << "getCurrentNavigationWaypoint() Not implemented by simpleVelocityNavigation";
+ yError() << "getCurrentNavigationWaypoint() Not implemented by " << m_localName;
return NOT_IMPLEMENTED;
}
bool simpleVelocityNavigation::suspendNavigation(double time)
{
- yError() << "suspendNavigation() Not implemented by simpleVelocityNavigation";
+ yError() << "suspendNavigation() Not implemented by " << m_localName;
return NOT_IMPLEMENTED;
}
bool simpleVelocityNavigation::resumeNavigation()
{
- yError() << "resumeNavigation() Not implemented by simpleVelocityNavigation";
+ yError() << "resumeNavigation() Not implemented by " << m_localName;
return NOT_IMPLEMENTED;
}
bool simpleVelocityNavigation::recomputeCurrentNavigationPath()
{
- yError() << "recomputeCurrentNavigationPath() Not implemented by simpleVelocityNavigation";
+ yError() << "recomputeCurrentNavigationPath() Not implemented by " << m_localName;
return NOT_IMPLEMENTED;
}
bool simpleVelocityNavigation::getCurrentNavigationMap(yarp::dev::NavigationMapTypeEnum map_type, MapGrid2D& map)
{
- yError() << "getCurrentNavigationMap() Not implemented by simpleVelocityNavigation";
+ yError() << "getCurrentNavigationMap() Not implemented by " << m_localName;
return NOT_IMPLEMENTED;
}
\ No newline at end of file
diff --git a/src/navigationDevices/simpleVelocityNavigation/simpleVelocityNavigation.h b/src/navigationDevices/simpleVelocityNavigation/simpleVelocityNavigation.h
index 60bd60dd..8d9b65ee 100644
--- a/src/navigationDevices/simpleVelocityNavigation/simpleVelocityNavigation.h
+++ b/src/navigationDevices/simpleVelocityNavigation/simpleVelocityNavigation.h
@@ -1,19 +1,9 @@
-/*
- * Copyright (C)2018 ICub Facility - Istituto Italiano di Tecnologia
- * Author: Marco Randazzo
- * email: marco.randazzo@iit.it
- * website: www.robotcub.org
- * Permission is granted to copy, distribute, and/or modify this program
- * under the terms of the GNU General Public License, version 2 or any
- * later version published by the Free Software Foundation.
- *
- * A copy of the license can be found at
- * http://www.robotcub.org/icub/license/gpl.txt
- *
- * This program is distributed in the hope that it will be useful, but
- * WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General
- * Public License for more details
+/*
+• Copyright (C) 2019 Istituto Italiano di Tecnologia (IIT)
+• All rights reserved.
+•
+• This software may be modified and distributed under the terms of the
+• GPL-2+ license. See the accompanying LICENSE file for details.
*/
#include
@@ -27,8 +17,8 @@
#include
#include
-#ifndef NAV_DEVICE_TEMPLATE_H
-#define NAV_DEVICE_TEMPLATE_H
+#ifndef SIMPLE_NAV_VELOCTY_H
+#define SIMPLE_NAV_VELOCTY_H
#define DEFAULT_THREAD_PERIOD 0.02 //s
@@ -60,8 +50,8 @@ class simpleVelocityNavigation : public yarp::os::PeriodicThread,
public:
simpleVelocityNavigation();
-private:
- void send_command(control_type control_data);
+protected:
+ virtual void send_command(control_type control_data);
public:
virtual bool open(yarp::os::Searchable& config) override;
@@ -76,7 +66,7 @@ class simpleVelocityNavigation : public yarp::os::PeriodicThread,
* @param loc the location to be reached
* @return true/false if the command is accepted
*/
- bool gotoTargetByAbsoluteLocation(yarp::dev::Nav2D::Map2DLocation loc) override;
+ virtual bool gotoTargetByAbsoluteLocation(yarp::dev::Nav2D::Map2DLocation loc) override;
/**
* Ask the robot to reach a position defined in the robot reference frame. The final orientation of the goal is unspecified.
@@ -84,14 +74,14 @@ class simpleVelocityNavigation : public yarp::os::PeriodicThread,
* @param y
* @return true/false
*/
- bool gotoTargetByRelativeLocation(double x, double y) override;
+ virtual bool gotoTargetByRelativeLocation(double x, double y) override;
/**
* //Sets a new relative target, expressed in local (robot) coordinate frame.
* @param v a three-element vector (x,y,theta) representing the location to be reached
* @return true/false if the command is accepted
*/
- bool gotoTargetByRelativeLocation(double x, double y, double theta) override;
+ virtual bool gotoTargetByRelativeLocation(double x, double y, double theta) override;
/**
* Apply a velocity command. velocities are expressed in the robot reference frame
@@ -108,52 +98,52 @@ class simpleVelocityNavigation : public yarp::os::PeriodicThread,
* @return a Map2DLocation containing data of the current target.
* @return true if a target is currently available, false otherwise (in this case returned target is invalid)
*/
- bool getAbsoluteLocationOfCurrentTarget(yarp::dev::Nav2D::Map2DLocation& target) override;
+ virtual bool getAbsoluteLocationOfCurrentTarget(yarp::dev::Nav2D::Map2DLocation& target) override;
/**
* //Gets the last target set through a setNewRelTarget command, expressed in absolute coordinates.
* @param a Map2DLocation containing data of the current target.
* @return true if a target is currently available, false otherwise (in this case returned target is invalid)
*/
- bool getRelativeLocationOfCurrentTarget(double& x, double& y, double& theta) override;
+ virtual bool getRelativeLocationOfCurrentTarget(double& x, double& y, double& theta) override;
/**
* //Gets the status of the current navigation task. Typically stored into navigation_status variable.
* @return the current navigation status expressed as NavigationStatusEnum.
*/
- bool getNavigationStatus(yarp::dev::NavigationStatusEnum& status) override;
+ virtual bool getNavigationStatus(yarp::dev::NavigationStatusEnum& status) override;
/**
* //Stops the current navigation task.
* @return true/false if the command is executed successfully.
*/
- bool stopNavigation() override;
+ virtual bool stopNavigation() override;
/**
* //Pauses the current navigation task.
* @return true/false if the command is executed successfully.
*/
- bool suspendNavigation(double time) override;
+ virtual bool suspendNavigation(double time) override;
/**
* //Resumes a previously paused navigation task.
* @return true/false if the command is executed successfully.
*/
- bool resumeNavigation() override;
+ virtual bool resumeNavigation() override;
/**
* Returns the list of waypoints generated by the navigation algorithm
* @param waypoints the list of waypoints generated by the navigation algorithm
* @return true/false
*/
- bool getAllNavigationWaypoints(yarp::dev::Nav2D::Map2DPath& waypoints) override;
+ virtual bool getAllNavigationWaypoints(yarp::dev::Nav2D::Map2DPath& waypoints) override;
/**
* Returns the current waypoint pursued by the navigation algorithm
* @param curr_waypoint the current waypoint pursued by the navigation algorithm
* @return true/false
*/
- bool getCurrentNavigationWaypoint(yarp::dev::Nav2D::Map2DLocation& curr_waypoint) override;
+ virtual bool getCurrentNavigationWaypoint(yarp::dev::Nav2D::Map2DLocation& curr_waypoint) override;
/**
* Returns the current navigation map processed by the navigation algorithm
@@ -161,14 +151,14 @@ class simpleVelocityNavigation : public yarp::os::PeriodicThread,
* @param map the map, currently used by the navigation algorithm
* @return true/false
*/
- bool getCurrentNavigationMap(yarp::dev::NavigationMapTypeEnum map_type, yarp::dev::Nav2D::MapGrid2D& map) override;
+ virtual bool getCurrentNavigationMap(yarp::dev::NavigationMapTypeEnum map_type, yarp::dev::Nav2D::MapGrid2D& map) override;
/**
* Forces the navigation system to recompute the path from the current robot position to the current goal.
* If no goal has been set, the command has no effect.
* @return true/false
*/
- bool recomputeCurrentNavigationPath() override;
+ virtual bool recomputeCurrentNavigationPath() override;
};
#endif
diff --git a/src/navigationDevices/simpleVelocityNavigationWithLaser/CMakeLists.txt b/src/navigationDevices/simpleVelocityNavigationWithLaser/CMakeLists.txt
new file mode 100644
index 00000000..0a14559d
--- /dev/null
+++ b/src/navigationDevices/simpleVelocityNavigationWithLaser/CMakeLists.txt
@@ -0,0 +1,32 @@
+yarp_prepare_plugin(simpleVelocityNavigationWithLaser
+ CATEGORY device
+ TYPE simpleVelocityNavigationWithLaser
+ INCLUDE simpleVelocityNavigationWithLaser.h)
+
+set(CMAKE_INCLUDE_CURRENT_DIR ON)
+
+yarp_add_plugin(simpleVelocityNavigationWithLaser
+ simpleVelocityNavigationWithLaser.h
+ simpleVelocityNavigationWithLaser.cpp
+ ../simpleVelocityNavigation/simpleVelocityNavigation.h
+ ../simpleVelocityNavigation/simpleVelocityNavigation.cpp)
+
+include_directories(include)
+
+target_link_libraries(simpleVelocityNavigationWithLaser YARP::YARP_OS
+ YARP::YARP_sig
+ YARP::YARP_dev
+ YARP::YARP_math
+ navigation_lib)
+
+yarp_install(TARGETS simpleVelocityNavigationWithLaser
+ EXPORT YARP_${YARP_PLUGIN_MASTER}
+ COMPONENT ${YARP_PLUGIN_MASTER}
+ LIBRARY DESTINATION ${NAVIGATION_DYNAMIC_PLUGINS_INSTALL_DIR}
+ ARCHIVE DESTINATION ${NAVIGATION_STATIC_PLUGINS_INSTALL_DIR}
+ YARP_INI DESTINATION ${NAVIGATION_PLUGIN_MANIFESTS_INSTALL_DIR})
+
+
+set(YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS ${YARP_${YARP_PLUGIN_MASTER}_PRIVATE_DEPS} PARENT_SCOPE)
+
+set_property(TARGET simpleVelocityNavigationWithLaser PROPERTY FOLDER "Plugins/Device")
diff --git a/src/navigationDevices/simpleVelocityNavigationWithLaser/simpleVelocityNavigationWithLaser.cpp b/src/navigationDevices/simpleVelocityNavigationWithLaser/simpleVelocityNavigationWithLaser.cpp
new file mode 100644
index 00000000..bdda75a3
--- /dev/null
+++ b/src/navigationDevices/simpleVelocityNavigationWithLaser/simpleVelocityNavigationWithLaser.cpp
@@ -0,0 +1,132 @@
+/*
+• Copyright (C) 2019 Istituto Italiano di Tecnologia (IIT)
+• All rights reserved.
+•
+• This software may be modified and distributed under the terms of the
+• GPL-2+ license. See the accompanying LICENSE file for details.
+*/
+
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include "simpleVelocityNavigationWithLaser.h"
+
+//the following ugly definition is just a reminder to check the system behavior when a method returns true (with invalid data) or false.
+#define NOT_IMPLEMENTED false
+
+using namespace yarp::os;
+using namespace yarp::dev;
+
+simpleVelocityNavigationWithLaser::simpleVelocityNavigationWithLaser() : simpleVelocityNavigation()
+{
+ m_localName = "simpleVelocityNavigationWithLaser";
+ m_obstacles_handler = nullptr;
+}
+
+bool simpleVelocityNavigationWithLaser::open(yarp::os::Searchable& config)
+{
+ //open the laser interface
+ Bottle laserBottle = config.findGroup("LASER");
+
+ if (laserBottle.isNull())
+ {
+ yError("LASER group not found,closing");
+ return false;
+ }
+
+ if (laserBottle.check("laser_port") == false)
+ {
+ yError("laser_port param not found,closing");
+ return false;
+ }
+ std::string laser_remote_port = laserBottle.find("laser_port").asString();
+
+ //opens the laser client and the corresponding interface
+ Property options;
+ options.put("device", "Rangefinder2DClient");
+ options.put("local", std::string("/")+m_localName+"/laser:i");
+ options.put("remote", laser_remote_port);
+ if (m_pLas.open(options) == false)
+ {
+ yError() << "Unable to open laser driver";
+ return false;
+ }
+ m_pLas.view(m_iLaser);
+ if (m_iLaser == 0)
+ {
+ yError() << "Unable to open laser interface";
+ return false;
+ }
+
+ m_obstacles_handler = new obstacles_class(config);
+
+ bool b = simpleVelocityNavigation::open(config);
+ return b;
+}
+
+bool simpleVelocityNavigationWithLaser::close()
+{
+ bool b = simpleVelocityNavigation::close();
+
+ if (m_pLas.isValid()) m_pLas.close();
+
+ if (m_obstacles_handler)
+ {
+ delete m_obstacles_handler;
+ m_obstacles_handler = nullptr;
+ }
+ return b;
+}
+
+bool simpleVelocityNavigationWithLaser::threadInit()
+{
+ return simpleVelocityNavigation::threadInit();
+}
+
+void simpleVelocityNavigationWithLaser::threadRelease()
+{
+ simpleVelocityNavigation::threadRelease();
+}
+
+void simpleVelocityNavigationWithLaser::run()
+{
+ simpleVelocityNavigation::run();
+}
+
+void simpleVelocityNavigationWithLaser::send_command(control_type control_data)
+{
+ //check the obstacle presence here
+ std::vector laser_data;
+ m_iLaser->getLaserMeasurement(laser_data);
+
+ //if obstacles are present, override robot velocity controls
+ if (m_obstacles_handler->check_obstacles_in_path(laser_data))
+ {
+ yWarning() << "Obstacles detected, robot is waiting!";
+ if (m_navigation_status == yarp::dev::navigation_status_moving)
+ {
+ m_navigation_status == yarp::dev::navigation_status_waiting_obstacle;
+ }
+ }
+
+ static yarp::os::Stamp stamp;
+ stamp.update();
+ Bottle &b = m_port_commands_output.prepare();
+ m_port_commands_output.setEnvelope(stamp);
+ b.clear();
+ b.addInt(BASECONTROL_COMMAND_VELOCIY_CARTESIAN);
+ b.addDouble(control_data.linear_xvel); // lin_vel in m/s
+ b.addDouble(control_data.linear_yvel); // lin_vel in m/s
+ b.addDouble(control_data.angular_vel); // ang_vel in deg/s
+ b.addDouble(100);
+ m_port_commands_output.write();
+}
+
diff --git a/src/navigationDevices/simpleVelocityNavigationWithLaser/simpleVelocityNavigationWithLaser.h b/src/navigationDevices/simpleVelocityNavigationWithLaser/simpleVelocityNavigationWithLaser.h
new file mode 100644
index 00000000..22971fd2
--- /dev/null
+++ b/src/navigationDevices/simpleVelocityNavigationWithLaser/simpleVelocityNavigationWithLaser.h
@@ -0,0 +1,58 @@
+/*
+• Copyright (C) 2019 Istituto Italiano di Tecnologia (IIT)
+• All rights reserved.
+•
+• This software may be modified and distributed under the terms of the
+• GPL-2+ license. See the accompanying LICENSE file for details.
+*/
+
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include "../simpleVelocityNavigation/simpleVelocityNavigation.h"
+#include
+
+#ifndef NAV_SIMPLE_VEL_NAV_WITH_LASER_H
+#define NAV_SIMPLE_VEL_NAV_WITH_LASER_H
+
+#define DEFAULT_THREAD_PERIOD 0.02 //s
+
+class simpleVelocityNavigationWithLaser :
+ public simpleVelocityNavigation
+ //public yarp::os::PeriodicThread,
+ //public yarp::dev::INavigation2DTargetActions,
+ //public yarp::dev::INavigation2DControlActions,
+ //public yarp::dev::DeviceDriver
+{
+protected:
+ //laser stuff
+ yarp::dev::PolyDriver m_pLas;
+ yarp::dev::IRangefinder2D* m_iLaser;
+
+ //obstacles stuff
+ obstacles_class* m_obstacles_handler;
+
+public:
+ simpleVelocityNavigationWithLaser();
+
+protected:
+ virtual void send_command(control_type control_data);
+
+public:
+ virtual bool open(yarp::os::Searchable& config) override;
+ virtual bool close() override;
+ virtual bool threadInit() override;
+ virtual void threadRelease() override;
+ virtual void run() override;
+
+};
+
+#endif