diff --git a/explore_stack/launch/combined_bringup.launch b/explore_stack/launch/combined_bringup.launch
index bc0b902..1992c39 100644
--- a/explore_stack/launch/combined_bringup.launch
+++ b/explore_stack/launch/combined_bringup.launch
@@ -11,8 +11,8 @@
-
-
+
+
diff --git a/cmd_vel_watchdog/CMakeLists.txt b/velocity_topic_watchdog/CMakeLists.txt
similarity index 96%
rename from cmd_vel_watchdog/CMakeLists.txt
rename to velocity_topic_watchdog/CMakeLists.txt
index cfd8eb6..0bc8850 100644
--- a/cmd_vel_watchdog/CMakeLists.txt
+++ b/velocity_topic_watchdog/CMakeLists.txt
@@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 2.8.3)
-project(cmd_vel_watchdog)
+project(velocity_topic_watchdog)
## Compile as C++11, supported in ROS Kinetic and newer
# add_compile_options(-std=c++11)
@@ -104,7 +104,7 @@ find_package(catkin REQUIRED COMPONENTS
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
# INCLUDE_DIRS include
-# LIBRARIES cmd_vel_watchdog
+# LIBRARIES velocity_topic_watchdog
# CATKIN_DEPENDS geometry_msgs roscpp rospy
# DEPENDS system_lib
)
@@ -122,7 +122,7 @@ include_directories(
## Declare a C++ library
# add_library(${PROJECT_NAME}
-# src/${PROJECT_NAME}/cmd_vel_watchdog.cpp
+# src/${PROJECT_NAME}/velocity_topic_watchdog.cpp
# )
## Add cmake target dependencies of the library
@@ -133,7 +133,7 @@ include_directories(
## Declare a C++ executable
## With catkin_make all packages are built within a single CMake context
## The recommended prefix ensures that target names across packages don't collide
-add_executable(cmd_vel_watchdog src/cmd_vel_watchdog.cpp)
+add_executable(velocity_topic_watchdog src/velocity_topic_watchdog.cpp)
## Rename C++ executable without prefix
## The above recommended prefix causes long target names, the following renames the
@@ -146,7 +146,7 @@ add_executable(cmd_vel_watchdog src/cmd_vel_watchdog.cpp)
# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
## Specify libraries to link a library or executable target against
- target_link_libraries(cmd_vel_watchdog
+ target_link_libraries(velocity_topic_watchdog
${catkin_LIBRARIES}
)
@@ -158,7 +158,7 @@ add_executable(cmd_vel_watchdog src/cmd_vel_watchdog.cpp)
## Install ##
#############
# install nodes
-install(TARGETS cmd_vel_watchdog
+install(TARGETS velocity_topic_watchdog
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
diff --git a/cmd_vel_watchdog/launch/cmd_vel_watchdog.launch b/velocity_topic_watchdog/launch/velocity_topic_watchdog.launch
similarity index 50%
rename from cmd_vel_watchdog/launch/cmd_vel_watchdog.launch
rename to velocity_topic_watchdog/launch/velocity_topic_watchdog.launch
index f394503..1e505a2 100644
--- a/cmd_vel_watchdog/launch/cmd_vel_watchdog.launch
+++ b/velocity_topic_watchdog/launch/velocity_topic_watchdog.launch
@@ -1,11 +1,11 @@
-
-
+
diff --git a/cmd_vel_watchdog/package.xml b/velocity_topic_watchdog/package.xml
similarity index 96%
rename from cmd_vel_watchdog/package.xml
rename to velocity_topic_watchdog/package.xml
index 9347b7f..5900b94 100644
--- a/cmd_vel_watchdog/package.xml
+++ b/velocity_topic_watchdog/package.xml
@@ -1,8 +1,8 @@
- cmd_vel_watchdog
+ velocity_topic_watchdog
0.0.0
- The cmd_vel_watchdog package
+ The velocity_topic_watchdog package
diff --git a/cmd_vel_watchdog/src/cmd_vel_watchdog.cpp b/velocity_topic_watchdog/src/velocity_topic_watchdog.cpp
similarity index 71%
rename from cmd_vel_watchdog/src/cmd_vel_watchdog.cpp
rename to velocity_topic_watchdog/src/velocity_topic_watchdog.cpp
index ab35b67..30e3914 100644
--- a/cmd_vel_watchdog/src/cmd_vel_watchdog.cpp
+++ b/velocity_topic_watchdog/src/velocity_topic_watchdog.cpp
@@ -5,7 +5,7 @@
#include
#include
-namespace cmd_vel_watchdog{
+namespace velocity_topic_watchdog{
ros::Publisher *pub_ptr;
ros::Timer *global_timer;
@@ -16,7 +16,7 @@ ros::Duration *watchdog_duration;
double watchdog_timeout_param (3.0);
void watchdogTimerCallback(const ros::TimerEvent &timerEvent){
- ROS_WARN_STREAM("velocity topic watchdog activated!");
+ ROS_WARN_STREAM("velocity_topic_watchdog activated!");
pub_ptr->publish(*stop_msg_ptr);
ROS_WARN_STREAM("STOP MSG PUBLISHED to [" << pub_ptr->getTopic() << "]");
global_timer->stop();
@@ -63,20 +63,20 @@ void commandVelocityReceived(const geometry_msgs::Twist &msgIn){
}
-} // namespace cmd_vel_watchdog
+} // namespace velocity_topic_watchdog
int main(int argc, char** argv){
- ros::init(argc, argv, "cmd_vel_watchdog");
+ ros::init(argc, argv, "velocity_topic_watchdog");
ros::NodeHandle nh;
- if (!nh.getParam("watchdog_patience", cmd_vel_watchdog::watchdog_timeout_param)){
+ if (!nh.getParam("watchdog_patience", velocity_topic_watchdog::watchdog_timeout_param)){
ROS_INFO_STREAM(
"watchdog_patience param is not found, setting to default = " <<
- cmd_vel_watchdog::DEFAULT_WATCHDOG_TIMEOUT << " sec");
- cmd_vel_watchdog::watchdog_timeout_param = cmd_vel_watchdog::DEFAULT_WATCHDOG_TIMEOUT;
+ velocity_topic_watchdog::DEFAULT_WATCHDOG_TIMEOUT << " sec");
+ velocity_topic_watchdog::watchdog_timeout_param = velocity_topic_watchdog::DEFAULT_WATCHDOG_TIMEOUT;
}
- ROS_INFO_STREAM("watchdog time set to " << cmd_vel_watchdog::watchdog_timeout_param << " [sec]");
+ ROS_INFO_STREAM("watchdog time set to " << velocity_topic_watchdog::watchdog_timeout_param << " [sec]");
- cmd_vel_watchdog::initGlobals(nh);
+ velocity_topic_watchdog::initGlobals(nh);
@@ -84,11 +84,11 @@ int main(int argc, char** argv){
const std::string &this_node_name = ros::this_node::getName();
ROS_INFO_STREAM(this_node_name << " created");
- cmd_vel_watchdog::pub_ptr = new ros::Publisher(nh.advertise(default_velocity_topic, 1));
+ velocity_topic_watchdog::pub_ptr = new ros::Publisher(nh.advertise(default_velocity_topic, 1));
- ROS_INFO_STREAM(this_node_name <<" advertised publisher to " << cmd_vel_watchdog::pub_ptr->getTopic());
+ ROS_INFO_STREAM(this_node_name <<" advertised publisher to " << velocity_topic_watchdog::pub_ptr->getTopic());
- ros::Subscriber sub = nh.subscribe(default_velocity_topic, 1, &cmd_vel_watchdog::commandVelocityReceived);
+ ros::Subscriber sub = nh.subscribe(default_velocity_topic, 1, &velocity_topic_watchdog::commandVelocityReceived);
ROS_INFO_STREAM(this_node_name <<" subscribed to topic " << sub.getTopic());
while(ros::ok()){
@@ -96,8 +96,8 @@ int main(int argc, char** argv){
}
ROS_WARN_STREAM(this_node_name <<" SHUT_DOWN ");
- delete cmd_vel_watchdog::pub_ptr;
- delete cmd_vel_watchdog::global_timer;
- delete cmd_vel_watchdog::stop_msg_ptr;
- delete cmd_vel_watchdog::watchdog_duration;
+ delete velocity_topic_watchdog::pub_ptr;
+ delete velocity_topic_watchdog::global_timer;
+ delete velocity_topic_watchdog::stop_msg_ptr;
+ delete velocity_topic_watchdog::watchdog_duration;
}
\ No newline at end of file