diff --git a/modules/catkin_ws/less b/modules/catkin_ws/less new file mode 100644 index 0000000000000000000000000000000000000000..5b8e6d39a982673a415c7e917a6549fd363c10a5 --- /dev/null +++ b/modules/catkin_ws/less @@ -0,0 +1,88 @@ +[0m[ INFO] [1521718243.071038508]: Initializing nodelet with 16 worker threads.[0m +[0m[ INFO] [1521718243.080567261]: Environment::onInit -- START[0m +[0m[ INFO] [1521718243.120601869]: Environment::onInit -- END[0m +[0m[ INFO] [1521718243.126112582]: Ultrasonic::onInit -- START[0m +[0m[ INFO] [1521718243.127296067]: Ultrasonic::onInit -- END[0m +Called MainNode(). +[0m[ INFO] [1521718243.131586669]: MainNode::onInit -- START[0m +[0m[ INFO] [1521718243.136267795]: MainNode::onInit -- END[0m +[0m[ INFO] [1521718243.139709753]: Camera::onInit -- START[0m +[0m[ INFO] [1521718243.140808953]: Camera::onInit -- END[0m +[0m[ INFO] [1521718243.144232873]: Lanekeeping::onInit -- START[0m +[0m[ INFO] [1521718243.148060006]: Lanekeeping::onInit -- END[0m +[0m[ INFO] [1521718243.151645771]: MavLink::onInit -- START[0m +[0m[ INFO] [1521718243.162937607]: MavLink::onInit -- END[0m +[0m[ INFO] [1521718243.167137851]: Logging::onInit -- START[0m +[0m[ INFO] [1521718243.222565839]: Logging::onInit -- END[0m +Environment recived new uss data (0). +Environment recived new cam data ( ). +MainNode recived new environmentData data (0, 1). +Logging received new environment data ( ). +Environment recived new uss data (1). +Environment received new uss data ( ). +MainNode recived new environmentData data (1, 1). +Logging received new environment data ( ). +Environment recived new cam data ( ). +Lanekeeping recived new cam data ( ). +Logging received new cam data ( ). +Environment recived new uss data (2). +Environment received new uss data ( ). +MainNode recived new environmentData data (2, 1). +Logging received new environment data ( ). +Environment recived new cam data ( ). +Lanekeeping recived new cam data ( ). +Logging received new cam data ( ). +Environment recived new uss data (3). +Environment received new uss data ( ). +MainNode recived new environmentData data (3, 1). +Logging received new environment data ( ). +Environment recived new cam data ( ). +Lanekeeping recived new cam data ( ). +Logging received new cam data ( ). +... logging to /home/philipp/.ros/log/f1d86846-2dba-11e8-933d-dc53600aa2a3/roslaunch-philipp-ThinkPad-L450-6448.log +Checking log directory for disk usage. This may take awhile. +Press Ctrl-C to interrupt +Done checking log file disk usage. Usage is <1GB. +]2;/home/philipp/hu/Hochautomatisiertes Fahren/Repo/modules/catkin_ws/src/car/launch/fullstart.launch +[1mstarted roslaunch server http://philipp-ThinkPad-L450:37696/[0m + +SUMMARY +======== + +PARAMETERS + * /Master/num_worker_threads: 16 + * /rosdistro: kinetic + * /rosversion: 1.12.12 + +NODES + / + Master (nodelet/nodelet) + nodelet_camera (nodelet/nodelet) + nodelet_environment (nodelet/nodelet) + nodelet_lanekeeping (nodelet/nodelet) + nodelet_logging (nodelet/nodelet) + nodelet_main_node (nodelet/nodelet) + nodelet_mav_link (nodelet/nodelet) + nodelet_ultrasonic (nodelet/nodelet) + +[1mROS_MASTER_URI=http://localhost:11311[0m +]2;/home/philipp/hu/Hochautomatisiertes Fahren/Repo/modules/catkin_ws/src/car/launch/fullstart.launch http://localhost:11311 +[1mprocess[Master-1]: started with pid [6465][0m +[1mprocess[nodelet_main_node-2]: started with pid [6466][0m +[1mprocess[nodelet_environment-3]: started with pid [6467][0m +[1mprocess[nodelet_ultrasonic-4]: started with pid [6469][0m +[1mprocess[nodelet_camera-5]: started with pid [6488][0m +[1mprocess[nodelet_lanekeeping-6]: started with pid [6505][0m +[1mprocess[nodelet_mav_link-7]: started with pid [6541][0m +[1mprocess[nodelet_logging-8]: started with pid [6559][0m +[nodelet_logging-8] killing on exit +[nodelet_mav_link-7] killing on exit +[nodelet_lanekeeping-6] killing on exit +[nodelet_camera-5] killing on exit +[nodelet_environment-3] killing on exit +[nodelet_ultrasonic-4] killing on exit +[Master-1] killing on exit +[nodelet_main_node-2] killing on exit +shutting down processing monitor... +... shutting down processing monitor complete +[1mdone[0m diff --git a/modules/catkin_ws/src/car/CMakeLists.txt b/modules/catkin_ws/src/car/CMakeLists.txt index 030ce89b1fcf7fd0aef3e78993b9af4b1d41d67a..93bbf7d685aecb9ea26238cd4d9065ba36828e81 100644 --- a/modules/catkin_ws/src/car/CMakeLists.txt +++ b/modules/catkin_ws/src/car/CMakeLists.txt @@ -51,10 +51,10 @@ include_directories( ) set(MAIN_NODE_SOURCE_FILES - include/mainNode/mainNode.h + include/mainNode/MainNode.h include/mainNode/NotifiableThread.h include/mainNode/PlatoonController.h - src/mainNode/mainNode.cpp + src/mainNode/MainNode.cpp src/mainNode/NotifiableThread.cpp src/mainNode/PlatoonController.cpp) @@ -79,23 +79,27 @@ target_include_directories(main_node PUBLIC ${PlatoonProtocolLib_INCLUDE_DIRS} ${PC2CarLib_INCLUDE_DIRS}) -add_library(environment src/environment/environment.cpp) +add_library(environment src/environment/Environment.cpp) add_dependencies(environment ${catkin_EXPORTED_TARGETS} ${PROJECT_NAME}_generate_messages_cpp) target_link_libraries(environment ${catkin_LIBRARIES}) -add_library(ultrasonic src/ultrasonic/ultrasonic.cpp) +add_library(logging src/logging/Logging.cpp) +add_dependencies(logging ${catkin_EXPORTED_TARGETS} ${PROJECT_NAME}_generate_messages_cpp) +target_link_libraries(logging ${catkin_LIBRARIES}) + +add_library(ultrasonic src/ultrasonic/Ultrasonic.cpp) add_dependencies(ultrasonic ${catkin_EXPORTED_TARGETS} ${PROJECT_NAME}_generate_messages_cpp) target_link_libraries(ultrasonic ${catkin_LIBRARIES}) -add_library(camera src/camera/camera.cpp) +add_library(camera src/camera/Camera.cpp) add_dependencies(camera ${catkin_EXPORTED_TARGETS} ${PROJECT_NAME}_generate_messages_cpp) target_link_libraries(camera ${catkin_LIBRARIES}) -add_library(lanekeeping src/lanekeeping/lanekeeping.cpp) +add_library(lanekeeping src/lanekeeping/Lanekeeping.cpp) add_dependencies(lanekeeping ${catkin_EXPORTED_TARGETS} ${PROJECT_NAME}_generate_messages_cpp) target_link_libraries(lanekeeping ${catkin_LIBRARIES}) -add_library(mav_link src/mavLink/mavLink.cpp) +add_library(mav_link src/mavLink/MavLink.cpp) add_dependencies(mav_link ${catkin_EXPORTED_TARGETS} ${PROJECT_NAME}_generate_messages_cpp) target_link_libraries(mav_link ${catkin_LIBRARIES}) diff --git a/modules/catkin_ws/src/car/include/camera/camera.h b/modules/catkin_ws/src/car/include/camera/Camera.h similarity index 100% rename from modules/catkin_ws/src/car/include/camera/camera.h rename to modules/catkin_ws/src/car/include/camera/Camera.h diff --git a/modules/catkin_ws/src/car/include/environment/Environment.h b/modules/catkin_ws/src/car/include/environment/Environment.h new file mode 100644 index 0000000000000000000000000000000000000000..00f1970048235fb39ae1ddd792a5c5f3b787b36d --- /dev/null +++ b/modules/catkin_ws/src/car/include/environment/Environment.h @@ -0,0 +1,40 @@ +#ifndef ENVIRONMENT_H +#define ENVIRONMENT_H + +#include <nodelet/nodelet.h> +#include <ros/ros.h> + +#include "car/ussDataMsg.h" +#include "car/camDataMsg.h" + +namespace car +{ +class Environment : public nodelet::Nodelet +{ +public: + virtual void onInit(); + + Environment(ros::NodeHandle & nh, std::string & name); + + Environment(); + + ~Environment(); + +private: + ros::NodeHandle nh_; + std::string name_; + + float distance; + float prevSpeed; + + ros::Publisher environmentData; + ros::Subscriber ussData; + ros::Subscriber camData; + + + void ussDataCallback(const ussDataMsg::ConstPtr & inMsg); + + void camDataCallback(const camDataMsg::ConstPtr & inMsg); +}; +} +#endif diff --git a/modules/catkin_ws/src/car/include/environment/environment.h b/modules/catkin_ws/src/car/include/environment/environment.h deleted file mode 100644 index 58e7ab6871bb5e039e28367aaf389a2e8a222296..0000000000000000000000000000000000000000 --- a/modules/catkin_ws/src/car/include/environment/environment.h +++ /dev/null @@ -1,35 +0,0 @@ -#ifndef ENVIRONMENT_H -#define ENVIRONMENT_H - -#include <nodelet/nodelet.h> -#include <ros/ros.h> - -#include "car/ussDataMsg.h" -#include "car/camDataMsg.h" - -namespace car -{ - class Environment : public nodelet::Nodelet - { - public: - virtual void onInit(); - Environment(ros::NodeHandle &nh, std::string &name); - Environment(); - ~Environment(); - private: - ros::NodeHandle nh_; - std::string name_; - - float distance; - float prevSpeed; - - ros::Publisher environmentData; - ros::Subscriber ussData; - ros::Subscriber camData; - - - void ussDataCallback(const ussDataMsg::ConstPtr& inMsg); - void camDataCallback(const camDataMsg::ConstPtr& inMsg); - }; -} -#endif diff --git a/modules/catkin_ws/src/car/include/lanekeeping/lanekeeping.h b/modules/catkin_ws/src/car/include/lanekeeping/Lanekeeping.h similarity index 100% rename from modules/catkin_ws/src/car/include/lanekeeping/lanekeeping.h rename to modules/catkin_ws/src/car/include/lanekeeping/Lanekeeping.h diff --git a/modules/catkin_ws/src/car/include/logging/Logging.h b/modules/catkin_ws/src/car/include/logging/Logging.h new file mode 100644 index 0000000000000000000000000000000000000000..0c0f969ceed7e362596775f3deba84932d187b6f --- /dev/null +++ b/modules/catkin_ws/src/car/include/logging/Logging.h @@ -0,0 +1,60 @@ +// +// Created by philipp on 22.03.18. +// + +#ifndef MODULES_LOGGING_H +#define MODULES_LOGGING_H + +#include <nodelet/nodelet.h> +#include <ros/ros.h> + +#include "car/camDataMsg.h" +#include "car/ccDataMsg.h" +#include "car/environmentDataMsg.h" +#include "car/laneDataMsg.h" +#include "car/logEnabledMsg.h" +#include "car/logStringMsg.h" +#include "car/rcEnabledMsg.h" +#include "car/stmDataMsg.h" +#include "car/ussDataMsg.h" + +namespace car +{ +class Logging : public nodelet::Nodelet +{ +public: + virtual void onInit(); + + Logging(ros::NodeHandle & nh, std::string & name); + + Logging(); + + ~Logging(); + +private: + ros::NodeHandle nh_; + std::string name_; + + ros::Subscriber camData; + ros::Subscriber ccData; + ros::Subscriber environmentData; + ros::Subscriber laneData; + ros::Subscriber logEnabled; + ros::Subscriber logString; + ros::Subscriber rcEnabled; + ros::Subscriber stmData; + ros::Subscriber ussData; + + void camDataCallback(const camDataMsg::ConstPtr & inMsg); + void ccDataCallback(const ccDataMsg::ConstPtr & inMsg); + void environmentDataCallback(const environmentDataMsg::ConstPtr & inMsg); + void laneDataCallback(const laneDataMsg::ConstPtr & inMsg); + void logEnabledCallback(const logEnabledMsg::ConstPtr & inMsg); + void logStringCallback(const logStringMsg::ConstPtr & inMsg); + void rcEnabledCallback(const rcEnabledMsg::ConstPtr & inMsg); + void stmDataCallback(const stmDataMsg::ConstPtr & inMsg); + void ussDataCallback(const ussDataMsg::ConstPtr & inMsg); +}; +} + +#endif //MODULES_LOGGING_H diff --git a/modules/catkin_ws/src/car/include/mainNode/mainNode.h b/modules/catkin_ws/src/car/include/mainNode/MainNode.h similarity index 100% rename from modules/catkin_ws/src/car/include/mainNode/mainNode.h rename to modules/catkin_ws/src/car/include/mainNode/MainNode.h diff --git a/modules/catkin_ws/src/car/include/mavLink/mavLink.h b/modules/catkin_ws/src/car/include/mavLink/MavLink.h similarity index 100% rename from modules/catkin_ws/src/car/include/mavLink/mavLink.h rename to modules/catkin_ws/src/car/include/mavLink/MavLink.h diff --git a/modules/catkin_ws/src/car/include/ultrasonic/ultrasonic.h b/modules/catkin_ws/src/car/include/ultrasonic/Ultrasonic.h similarity index 100% rename from modules/catkin_ws/src/car/include/ultrasonic/ultrasonic.h rename to modules/catkin_ws/src/car/include/ultrasonic/Ultrasonic.h diff --git a/modules/catkin_ws/src/car/launch/fullstart.launch b/modules/catkin_ws/src/car/launch/fullstart.launch index 26f97c0b45bded7061cf299f0ab88ba61fdd26e0..c8f24d5bc13b17fe27fbd78372cb271b8124b936 100644 --- a/modules/catkin_ws/src/car/launch/fullstart.launch +++ b/modules/catkin_ws/src/car/launch/fullstart.launch @@ -9,6 +9,7 @@ <node pkg="nodelet" type="nodelet" name="nodelet_camera" args="load car/camera Master"/> <node pkg="nodelet" type="nodelet" name="nodelet_lanekeeping" args="load car/lanekeeping Master"/> <node pkg="nodelet" type="nodelet" name="nodelet_mav_link" args="load car/mav_link Master"/> + <node pkg="nodelet" type="nodelet" name="nodelet_logging" args="load car/logging Master"/> </launch> <!-- diff --git a/modules/catkin_ws/src/car/plugins/nodelet_plugins.xml b/modules/catkin_ws/src/car/plugins/nodelet_plugins.xml index f41107561d1b1d855f4d742002355f022225c274..b39f41628573410da1ef9bdf388123e4caba3477 100644 --- a/modules/catkin_ws/src/car/plugins/nodelet_plugins.xml +++ b/modules/catkin_ws/src/car/plugins/nodelet_plugins.xml @@ -24,6 +24,16 @@ </class> </library> +<library path="lib/liblogging"> +<class name="car/logging" + type="car::Logging" + base_class_type="nodelet::Nodelet"> + <description> + Missing + </description> +</class> +</library> + <library path="lib/libultrasonic"> <class name="car/ultrasonic" type="car::Ultrasonic" diff --git a/modules/catkin_ws/src/car/src/camera/Camera.cpp b/modules/catkin_ws/src/car/src/camera/Camera.cpp new file mode 100644 index 0000000000000000000000000000000000000000..fb71a63fe793b516ab2cb6a10a44748308583c49 --- /dev/null +++ b/modules/catkin_ws/src/car/src/camera/Camera.cpp @@ -0,0 +1,40 @@ +#include <pluginlib/class_list_macros.h> +#include <ros/ros.h> + +#include "camera/Camera.h" + +#include "car/camDataMsg.h" + +PLUGINLIB_EXPORT_CLASS(car::Camera, nodelet::Nodelet); + +namespace car +{ + +Camera::Camera(ros::NodeHandle & nh, std::string & name) : nh_(nh), name_(name) +{} + +Camera::Camera() +{} + +Camera::~Camera() +{} + +void Camera::onInit() +{ + NODELET_INFO("Camera::onInit -- START"); + camData = nh_.advertise<camDataMsg>("camData", 1); + main = boost::thread( + [this]() + { + ros::Rate rate{1}; + while (ros::ok()) + { + camDataMsg msg; + camData.publish(msg); + rate.sleep(); + } + }); + + NODELET_INFO("Camera::onInit -- END"); +} +} diff --git a/modules/catkin_ws/src/car/src/camera/camera.cpp b/modules/catkin_ws/src/car/src/camera/camera.cpp deleted file mode 100644 index 699b1810afb7e56aa1f9ba191b00ffacefe806ca..0000000000000000000000000000000000000000 --- a/modules/catkin_ws/src/car/src/camera/camera.cpp +++ /dev/null @@ -1,30 +0,0 @@ -#include <pluginlib/class_list_macros.h> -#include <ros/ros.h> - -#include "camera/camera.h" - -#include "car/camDataMsg.h" - -PLUGINLIB_EXPORT_CLASS(car::Camera, nodelet::Nodelet); - -namespace car -{ - Camera::Camera(ros::NodeHandle &nh, std::string &name) : nh_(nh), name_(name) {} - Camera::Camera() {} - Camera::~Camera() {} - void Camera::onInit() - { - NODELET_INFO("Camera::onInit -- START"); - camData = nh_.advertise<camDataMsg>("camData", 1); - main = boost::thread([this] () { - ros::Rate rate{1}; - while(ros::ok()) { - camDataMsg msg; - camData.publish(msg); - rate.sleep(); - } - }); - - NODELET_INFO("Camera::onInit -- END"); - } -} diff --git a/modules/catkin_ws/src/car/src/environment/environment.cpp b/modules/catkin_ws/src/car/src/environment/Environment.cpp similarity index 97% rename from modules/catkin_ws/src/car/src/environment/environment.cpp rename to modules/catkin_ws/src/car/src/environment/Environment.cpp index b1b7e684748bb4fd951ed8c4f79c5ac419c6f03a..ed418339494868d9963afe2d01a5116ec54b23c0 100644 --- a/modules/catkin_ws/src/car/src/environment/environment.cpp +++ b/modules/catkin_ws/src/car/src/environment/Environment.cpp @@ -1,7 +1,7 @@ #include <pluginlib/class_list_macros.h> #include <ros/ros.h> -#include "environment/environment.h" +#include "environment/Environment.h" #include "car/camDataMsg.h" #include "car/environmentDataMsg.h" diff --git a/modules/catkin_ws/src/car/src/lanekeeping/lanekeeping.cpp b/modules/catkin_ws/src/car/src/lanekeeping/Lanekeeping.cpp similarity index 95% rename from modules/catkin_ws/src/car/src/lanekeeping/lanekeeping.cpp rename to modules/catkin_ws/src/car/src/lanekeeping/Lanekeeping.cpp index 363f3d5456c2acc442589988aa52d760cd480c5b..b072e46ec8589c13071dc095b922f7f65e3707f4 100644 --- a/modules/catkin_ws/src/car/src/lanekeeping/lanekeeping.cpp +++ b/modules/catkin_ws/src/car/src/lanekeeping/Lanekeeping.cpp @@ -1,7 +1,7 @@ #include <pluginlib/class_list_macros.h> #include <ros/ros.h> -#include "lanekeeping/lanekeeping.h" +#include "lanekeeping/Lanekeeping.h" #include "car/camDataMsg.h" #include "car/environmentDataMsg.h" diff --git a/modules/catkin_ws/src/car/src/logging/Logging.cpp b/modules/catkin_ws/src/car/src/logging/Logging.cpp new file mode 100644 index 0000000000000000000000000000000000000000..688eacfdee0d3c23348927686752dca0ffac2429 --- /dev/null +++ b/modules/catkin_ws/src/car/src/logging/Logging.cpp @@ -0,0 +1,88 @@ +// +// Created by philipp on 22.03.18. +// + +#include <pluginlib/class_list_macros.h> +#include <ros/ros.h> + +#include "logging/Logging.h" + +PLUGINLIB_EXPORT_CLASS(car::Logging, nodelet::Nodelet +); + +namespace car +{ + +Logging::Logging(ros::NodeHandle & nh, std::string & name) : + nh_(nh), name_(name) +{} + +Logging::Logging() +{} + +Logging::~Logging() +{} + +void Logging::onInit() +{ + NODELET_INFO("Logging::onInit -- START"); + + camData = nh_.subscribe("camData", 1, &Logging::camDataCallback, this); + ccData = nh_.subscribe("ccData", 1, &Logging::ccDataCallback, this); + environmentData = nh_.subscribe("environmentData", 1, &Logging::environmentDataCallback, this); + laneData = nh_.subscribe("laneData", 1, &Logging::laneDataCallback, this); + logEnabled = nh_.subscribe("logEnabled", 1, &Logging::logEnabledCallback, this); + logString = nh_.subscribe("logString", 1, &Logging::logStringCallback, this); + rcEnabled = nh_.subscribe("rcEnabled", 1, &Logging::rcEnabledCallback, this); + stmData = nh_.subscribe("stmData", 1, &Logging::stmDataCallback, this); + ussData = nh_.subscribe("ussData", 1, &Logging::ussDataCallback, this); + + NODELET_INFO("Logging::onInit -- END"); +} + +void Logging::ccDataCallback(const ccDataMsg::ConstPtr & inMsg) +{ + std::cout << "Logging received new cc data ( ).\n"; +} + +void Logging::camDataCallback(const camDataMsg::ConstPtr & inMsg) +{ + std::cout << "Logging received new cam data ( ).\n"; +} + +void Logging::environmentDataCallback(const environmentDataMsg::ConstPtr & inMsg) +{ + std::cout << "Logging received new environment data ( ).\n"; +} + +void Logging::laneDataCallback(const laneDataMsg::ConstPtr & inMsg) +{ + std::cout << "Logging received new lane data ( ).\n"; +} + +void Logging::logEnabledCallback(const logEnabledMsg::ConstPtr & inMsg) +{ + std::cout << "Logging received new log enabled ( ).\n"; +} + +void Logging::logStringCallback(const logStringMsg::ConstPtr & inMsg) +{ + std::cout << "Logging received new log string ( ).\n"; +} + +void Logging::rcEnabledCallback(const rcEnabledMsg::ConstPtr & inMsg) +{ + std::cout << "Logging received new rc enabled ( ).\n"; +} + +void Logging::stmDataCallback(const stmDataMsg::ConstPtr & inMsg) +{ + std::cout << "Logging received new stm data ( ).\n"; +} + +void Logging::ussDataCallback(const ussDataMsg::ConstPtr & inMsg) +{ + std::cout << "Logging received new uss data ( ).\n"; +} + +} \ No newline at end of file diff --git a/modules/catkin_ws/src/car/src/mainNode/mainNode.cpp b/modules/catkin_ws/src/car/src/mainNode/MainNode.cpp similarity index 98% rename from modules/catkin_ws/src/car/src/mainNode/mainNode.cpp rename to modules/catkin_ws/src/car/src/mainNode/MainNode.cpp index 9be2fc067163150aedfa78b70c19971925ea9f37..b489b9c9756a459efdc57e1e8056a1cd497b6c83 100644 --- a/modules/catkin_ws/src/car/src/mainNode/mainNode.cpp +++ b/modules/catkin_ws/src/car/src/mainNode/MainNode.cpp @@ -1,7 +1,7 @@ #include <pluginlib/class_list_macros.h> #include <ros/ros.h> -#include "mainNode/mainNode.h" +#include "mainNode/MainNode.h" #include "car/camDataMsg.h" #include "car/ccDataMsg.h" diff --git a/modules/catkin_ws/src/car/src/mavLink/mavLink.cpp b/modules/catkin_ws/src/car/src/mavLink/MavLink.cpp similarity index 97% rename from modules/catkin_ws/src/car/src/mavLink/mavLink.cpp rename to modules/catkin_ws/src/car/src/mavLink/MavLink.cpp index 94246aac076976252847b42e35c675452ea35a84..6a735c5f9c5f82119173d34136820ae18e52b56e 100644 --- a/modules/catkin_ws/src/car/src/mavLink/mavLink.cpp +++ b/modules/catkin_ws/src/car/src/mavLink/MavLink.cpp @@ -1,7 +1,7 @@ #include <pluginlib/class_list_macros.h> #include <ros/ros.h> -#include "mavLink/mavLink.h" +#include "mavLink/MavLink.h" #include "car/stmDataMsg.h" #include "car/ccDataMsg.h" diff --git a/modules/catkin_ws/src/car/src/ultrasonic/Ultrasonic.cpp b/modules/catkin_ws/src/car/src/ultrasonic/Ultrasonic.cpp new file mode 100644 index 0000000000000000000000000000000000000000..987a684f2094fca6cd665f7bff6229a8b8a95a6f --- /dev/null +++ b/modules/catkin_ws/src/car/src/ultrasonic/Ultrasonic.cpp @@ -0,0 +1,42 @@ +#include <pluginlib/class_list_macros.h> +#include <ros/ros.h> + +#include "ultrasonic/Ultrasonic.h" + +#include "car/ussDataMsg.h" + +PLUGINLIB_EXPORT_CLASS(car::Ultrasonic, nodelet::Nodelet +); + +namespace car +{ +Ultrasonic::Ultrasonic(ros::NodeHandle & nh, std::string & name) : nh_(nh), name_(name) +{} + +Ultrasonic::Ultrasonic() +{} + +Ultrasonic::~Ultrasonic() +{} + +void Ultrasonic::onInit() +{ + NODELET_INFO("Ultrasonic::onInit -- START"); + ussData = nh_.advertise<ussDataMsg>("ussData", 1); + main = boost::thread( + [this]() + { + int counter = 0; + ros::Rate rate{1}; + while (ros::ok()) + { + ussDataMsg msg; + msg.distance = counter++; + ussData.publish(msg); + rate.sleep(); + } + }); + + NODELET_INFO("Ultrasonic::onInit -- END"); +} +} diff --git a/modules/catkin_ws/src/car/src/ultrasonic/ultrasonic.cpp b/modules/catkin_ws/src/car/src/ultrasonic/ultrasonic.cpp deleted file mode 100644 index 433b4c52fe8188d046520862cb549319645258ec..0000000000000000000000000000000000000000 --- a/modules/catkin_ws/src/car/src/ultrasonic/ultrasonic.cpp +++ /dev/null @@ -1,32 +0,0 @@ -#include <pluginlib/class_list_macros.h> -#include <ros/ros.h> - -#include "ultrasonic/ultrasonic.h" - -#include "car/ussDataMsg.h" - -PLUGINLIB_EXPORT_CLASS(car::Ultrasonic, nodelet::Nodelet); - -namespace car -{ - Ultrasonic::Ultrasonic(ros::NodeHandle &nh, std::string &name) : nh_(nh), name_(name) {} - Ultrasonic::Ultrasonic() {} - Ultrasonic::~Ultrasonic() {} - void Ultrasonic::onInit() - { - NODELET_INFO("Ultrasonic::onInit -- START"); - ussData = nh_.advertise<ussDataMsg>("ussData", 1); - main = boost::thread([this] () { - int counter = 0; - ros::Rate rate{1}; - while(ros::ok()) { - ussDataMsg msg; - msg.distance = counter++; - ussData.publish(msg); - rate.sleep(); - } - }); - - NODELET_INFO("Ultrasonic::onInit -- END"); - } -}