diff --git a/CMakeLists.txt b/CMakeLists.txt index 6d5ecc1bea7a74dee99e515d19b8c0e5d9ccd3ab..79190a0ef8244b5dc0064a8433c0f48fb00824c9 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -6,7 +6,7 @@ find_package(catkin REQUIRED) # ******************************************************************** # Add catkin additional components here # ******************************************************************** -find_package(catkin REQUIRED COMPONENTS iri_base_driver sensor_msgs) +find_package(catkin REQUIRED COMPONENTS iri_base_driver roscpp sensor_msgs) ## System dependencies are found with CMake's conventions find_package(Boost REQUIRED COMPONENTS thread) @@ -61,11 +61,11 @@ catkin_package( # ******************************************************************** # Add ROS and IRI ROS run time dependencies # ******************************************************************** - CATKIN_DEPENDS iri_base_driver sensor_msgs + CATKIN_DEPENDS iri_base_driver roscpp sensor_msgs # ******************************************************************** # Add system and labrobotica run time dependencies here # ******************************************************************** - DEPENDS lidar_lite usb_i2c_adapter + DEPENDS ) ########### diff --git a/cfg/LidarLiteDriver.cfg b/cfg/LidarLiteDriver.cfg index cfbf14a5369387be18901005faa3b48a9e31492d..5ad6986698f82542b9d2249f25b86f985e15b6e8 100755 --- a/cfg/LidarLiteDriver.cfg +++ b/cfg/LidarLiteDriver.cfg @@ -31,9 +31,9 @@ # Author: -PACKAGE='iri_lidar_lite' +PACKAGE='iri_lidar_lite_driver' -from driver_base.msg import SensorLevels +from iri_base_driver.msg import SensorLevels from dynamic_reconfigure.parameter_generator_catkin import * gen = ParameterGenerator() diff --git a/include/lidar_lite_driver.h b/include/lidar_lite_driver.h index b0e17a55c0ffc39caf23d262894b20060cc4efb5..64083ecf76d0827bb446a1cc9d0de0fec81d298c 100644 --- a/include/lidar_lite_driver.h +++ b/include/lidar_lite_driver.h @@ -28,7 +28,7 @@ #define _lidar_lite_driver_h_ #include <iri_base_driver/iri_base_driver.h> -#include <iri_lidar_lite/LidarLiteConfig.h> +#include <iri_lidar_lite_driver/LidarLiteConfig.h> #include <iridrivers/lidar_lite.h> #include <iridrivers/lidar_lite_exceptions.h> @@ -70,7 +70,7 @@ public: * Define a Config type with the LidarLiteConfig. All driver implementations * will then use the same variable type Config. */ - typedef iri_lidar_lite::LidarLiteConfig Config; + typedef iri_lidar_lite_driver::LidarLiteConfig Config; /** * \brief config variable diff --git a/package.xml b/package.xml index d49a4a491fec14a0a119c2c63d1dd04ddd7a9cc8..66990d94343a0927289a3ae4788214c93b3b05eb 100644 --- a/package.xml +++ b/package.xml @@ -42,8 +42,10 @@ <buildtool_depend>catkin</buildtool_depend> <build_depend>iri_base_driver</build_depend> <build_depend>sensor_msgs</build_depend> + <build_depend>roscpp</build_depend> <run_depend>iri_base_driver</run_depend> <run_depend>sensor_msgs</run_depend> + <run_depend>roscpp</run_depend> <!-- The export tag contains other, unspecified, tags --> diff --git a/src/lidar_lite_driver.cpp b/src/lidar_lite_driver.cpp index a137c01d1d29c1a4a8ab7fc1291961c97b348fe8..16d448eafb6d63e1cb33ee2996233fd3b13ad6a7 100644 --- a/src/lidar_lite_driver.cpp +++ b/src/lidar_lite_driver.cpp @@ -58,13 +58,13 @@ LidarLiteDriver::config_update(Config& new_cfg, uint32_t level) // depending on current state // update driver with new_cfg data switch (this->getState()) { - case LidarLiteDriver::CLOSED: + case iri_base_driver::CLOSED: break; - case LidarLiteDriver::OPENED: + case iri_base_driver::OPENED: break; - case LidarLiteDriver::RUNNING: + case iri_base_driver::RUNNING: this->config_mode_ = new_cfg.Config_mode; diff --git a/src/lidar_lite_driver_node.cpp b/src/lidar_lite_driver_node.cpp index 92b6a28c59146191e8c5cd9b0a0a9044779e10dd..3ab56951a45a3217226a77040f0ba710762a9f90 100644 --- a/src/lidar_lite_driver_node.cpp +++ b/src/lidar_lite_driver_node.cpp @@ -7,7 +7,7 @@ LidarLiteDriverNode::LidarLiteDriverNode(ros::NodeHandle& nh) // , RunThread_(true) // , Thread_(boost::bind(&LidarLiteDriverNode::ThreadFunc, this)) { - this->loop_rate_ = 30; // [Hz] + this->setRate(30); // Read from launch file std::string serial; @@ -67,7 +67,7 @@ void LidarLiteDriverNode::mainNodeThread(void) { /* code */ - if (this->driver_.getState() == LidarLiteDriver::RUNNING) { + if (this->driver_.isRunning()) { // Get measurement this->driver_.lock(); @@ -139,6 +139,5 @@ LidarLiteDriverNode::~LidarLiteDriverNode(void) int main(int argc, char* argv[]) { - return driver_base::main<LidarLiteDriverNode>(argc, argv, - "lidar_lite_driver_node"); + return iri_base_driver::main<LidarLiteDriverNode>(argc, argv,"lidar_lite_driver_node"); }