Переглянути джерело

add ros_observer. for autoware bridge.

yuchuli 3 роки тому
батько
коміт
f363fb1795

+ 89 - 0
src/ros/catkin/src/ros_observer/CMakeLists.txt

@@ -0,0 +1,89 @@
+cmake_minimum_required(VERSION 2.8.3)
+project(ros_observer)
+
+add_compile_options(-std=c++11)
+
+find_package(
+  catkin REQUIRED COMPONENTS
+  roscpp
+  roslint
+)
+
+find_package(Boost REQUIRED COMPONENTS
+  thread
+)
+
+set(ROSLINT_CPP_OPTS "--filter=-build/c++11")
+roslint_cpp()
+
+catkin_package(
+  INCLUDE_DIRS include
+  LIBRARIES lib_ros_observer
+)
+
+include_directories(
+  include
+  ${catkin_INCLUDE_DIRS}
+)
+
+add_executable(
+  ros_observer
+  src/ros_observer.cpp
+)
+
+target_link_libraries(
+  ros_observer
+  rt ${Boost_LIBRARIES}
+)
+
+add_dependencies(
+  ros_observer
+  ${catkin_EXPORTED_TARGETS}
+)
+
+add_library(
+  lib_ros_observer
+  lib/lib_ros_observer.cpp
+)
+
+target_link_libraries(
+  lib_ros_observer
+  ${catkin_LIBRARIES}
+  rt
+  ${Boost_LIBRARIES}
+)
+
+add_dependencies(
+  lib_ros_observer
+  ${catkin_EXPORTED_TARGETS}
+)
+
+# include header files
+install(DIRECTORY include/${PROJECT_NAME}/
+  DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
+)
+
+# Install library
+install(TARGETS ros_observer lib_ros_observer
+  ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
+  LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
+  RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
+)
+
+# Install launch
+install(DIRECTORY launch/
+  DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch
+)
+
+if (CATKIN_ENABLE_TESTING)
+  roslint_add_test()
+  find_package(rostest REQUIRED)
+  add_rostest_gtest(test_ros_observer
+    test/test_ros_observer.test
+    test/src/test_ros_observer.cpp
+  )
+  target_link_libraries(test_ros_observer
+    lib_ros_observer
+    ${catkin_LIBRARIES}
+  )
+endif()

+ 71 - 0
src/ros/catkin/src/ros_observer/include/ros_observer/lib_ros_observer.h

@@ -0,0 +1,71 @@
+#ifndef ROS_OBSERVER_LIB_ROS_OBSERVER_H
+#define ROS_OBSERVER_LIB_ROS_OBSERVER_H
+
+/*
+ * Copyright 2019 Autoware Foundation. All rights reserved.
+ *
+ * Licensed under the Apache License, Version 2.0 (the "License");
+ * you may not use this file except in compliance with the License.
+ * You may obtain a copy of the License at
+ *
+ *     http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS,
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+ * See the License for the specific language governing permissions and
+ * limitations under the License.
+ *
+ */
+
+#include <string>
+#include <boost/interprocess/managed_shared_memory.hpp>
+#include <boost/interprocess/sync/interprocess_mutex.hpp>
+#include <boost/interprocess/sync/scoped_lock.hpp>
+#include <boost/thread.hpp>
+
+#include <ros_observer/ros_observer.h>
+
+enum class VitalMonitorMode
+{
+  CNT_CLEAR,
+  CNT_MON
+};
+
+class ShmVitalMonitor
+{
+public:
+  ShmVitalMonitor(std::string mod_name, const double loop_rate, VitalMonitorMode mode = VitalMonitorMode::CNT_CLEAR);
+
+  void set_mode(VitalMonitorMode mode) {mode_ = mode;}
+  void run(void);
+  bool is_error_detected(void);
+
+protected:
+  std::string name_, shm_name_, mut_name_;
+  VitalMonitorMode mode_;
+  bool is_opened_;
+  const unsigned int polling_interval_msec_;
+
+  bool attempt_to_open(void);
+  void init_vital_counter(void);
+  void update_vital_counter(void);
+};
+
+class ShmDRStopRequest
+{
+public:
+  ShmDRStopRequest() :
+  is_opened_(false), name_("DRStopRequest"), shm_name_("SHM_" + name_), mut_name_("MUT_" + name_) {}
+
+  void clear_request(void);
+  bool is_request_received(void);
+
+protected:
+  bool is_opened_;
+  std::string name_, shm_name_, mut_name_;
+
+  bool attempt_to_open(void);
+};
+
+#endif  // ROS_OBSERVER_LIB_ROS_OBSERVER_H

+ 53 - 0
src/ros/catkin/src/ros_observer/include/ros_observer/ros_observer.h

@@ -0,0 +1,53 @@
+#ifndef ROS_OBSERVER_ROS_OBSERVER_H
+#define ROS_OBSERVER_ROS_OBSERVER_H
+
+/*
+ * Copyright 2019 Autoware Foundation. All rights reserved.
+ *
+ * Licensed under the Apache License, Version 2.0 (the "License");
+ * you may not use this file except in compliance with the License.
+ * You may obtain a copy of the License at
+ *
+ *     http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS,
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+ * See the License for the specific language governing permissions and
+ * limitations under the License.
+ *
+ */
+
+#include <iostream>
+#include <string>
+#include <functional>
+#include <utility>
+#include <boost/interprocess/managed_shared_memory.hpp>
+#include <boost/interprocess/sync/interprocess_mutex.hpp>
+#include <boost/interprocess/sync/scoped_lock.hpp>
+#include <boost/thread.hpp>
+
+static constexpr const char* SHM_NAME = "SharedMemoryForVitalMonitor";
+static constexpr int SHM_SIZE = 65536;
+static constexpr unsigned int SHM_TH_COUNTER = 3;
+static constexpr unsigned int SHM_COUNTER_MAX = 10000;
+
+enum class ModuleStatus
+{
+  Normal,
+  ErrorDetected
+};
+
+struct ShmVitalCounter
+{
+  ModuleStatus modstatus;
+
+  bool activated;
+  unsigned int thresh;
+  unsigned int value;
+
+  ShmVitalCounter() :
+  modstatus(ModuleStatus::Normal), activated(false), thresh(0), value(0) {}
+};
+
+#endif  // ROS_OBSERVER_ROS_OBSERVER_H

+ 4 - 0
src/ros/catkin/src/ros_observer/launch/ros_observer.launch

@@ -0,0 +1,4 @@
+<?xml version="1.0"?>
+<launch>
+    <node pkg="ros_observer" type="ros_observer" name="ros_observer" output="log" respawn="false" />
+</launch>

+ 6 - 0
src/ros/catkin/src/ros_observer/launch/test.launch

@@ -0,0 +1,6 @@
+<?xml version="1.0"?>
+<launch>
+    <node pkg="ros_observer" type="ros_observer" name="ros_observer" output="screen" respawn="false" respawn_delay="0" />
+    <arg name="shm_vmon_enabled" default="false"/>
+    <param name="shm_vmon_enabled" value="$(arg shm_vmon_enabled)"/>
+</launch>

+ 16 - 0
src/ros/catkin/src/ros_observer/package.xml

@@ -0,0 +1,16 @@
+<?xml version="1.0"?>
+<package format="2">
+  <name>ros_observer</name>
+  <version>1.12.0</version>
+  <description>The ros_observer package</description>
+  <author email="shingo.takeuchi.2@tier4.jp">Shingo Takeuchi</author>
+  <maintainer email="shingo.takeuchi.2@tier4.jp">Shingo Takeuchi</maintainer>
+  <license>Apache 2</license>
+  <buildtool_depend>catkin</buildtool_depend>
+  <build_depend>rostest</build_depend>
+  <depend>roscpp</depend>
+  <depend>boost</depend>
+  <depend>roslint</depend>
+  <export>
+  </export>
+</package>

+ 194 - 0
src/ros/catkin/src/ros_observer/src/ros_observer.cpp

@@ -0,0 +1,194 @@
+/*
+ * Copyright 2019 Autoware Foundation. All rights reserved.
+ *
+ * Licensed under the Apache License, Version 2.0 (the "License");
+ * you may not use this file except in compliance with the License.
+ * You may obtain a copy of the License at
+ *
+ *     http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS,
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+ * See the License for the specific language governing permissions and
+ * limitations under the License.
+ *
+ */
+
+#include <csignal>
+#include <chrono>
+#include <iostream>
+#include <string>
+#include <algorithm>
+#include <ros_observer/ros_observer.h>
+
+using boost::interprocess::managed_shared_memory;
+using boost::interprocess::interprocess_mutex;
+using boost::interprocess::shared_memory_object;
+using boost::interprocess::scoped_lock;
+using boost::interprocess::create_only;
+
+static void sig_handler_init(void);
+static void sig_handler(void);
+
+static constexpr double ROS_OBSERVE_MONITOR_RATE = 100;
+static constexpr unsigned int POLLING_INTERVAL_MSEC = (1000.0 / ROS_OBSERVE_MONITOR_RATE);
+static constexpr unsigned int POLLING_INTERVAL_USEC = (POLLING_INTERVAL_MSEC * 1000);
+static constexpr unsigned int SHM_TH_COUNTER_RO = 10;
+
+static bool terminate_req_rcvd = false;
+
+// Signal Handler
+static void sig_handler(int signo)
+{
+  terminate_req_rcvd = true;
+}
+
+// Signal Handler Initialization
+static void sig_handler_init(void)
+{
+  if (signal(SIGUSR1, sig_handler) == SIG_ERR)
+  {
+    std::cout << "[INFO][Cannot catch SIGUSR1]" << std::endl;
+  }
+
+  if (signal(SIGTERM, sig_handler) == SIG_ERR)
+  {
+    std::cout << "[INFO][Cannot catch SIGTERM]" << std::endl;
+  }
+
+  if (signal(SIGINT, sig_handler) == SIG_ERR)
+  {
+    std::cout << "[INFO][Cannot catch SIGINT]" << std::endl;
+  }
+
+  if (signal(SIGQUIT, sig_handler) == SIG_ERR)
+  {
+    std::cout << "[INFO][Cannot catch SIGQUIT]" << std::endl;
+  }
+}
+
+int main(int argc, char* argv[])
+{
+  sig_handler_init();
+
+  struct tm localtime;
+  auto now = std::chrono::system_clock::now();
+  auto now_c = std::chrono::system_clock::to_time_t(now);
+  localtime_r(&now_c, &localtime);
+  std::cout << "[START][TIME][LOCAL: " << std::put_time(&localtime, "%c") << "]" << std::endl;
+
+  shared_memory_object::remove(SHM_NAME);
+  managed_shared_memory shm(create_only, SHM_NAME, SHM_SIZE);
+
+  ShmVitalCounter* p_cnt_RO = shm.construct<ShmVitalCounter>("SHM_RosObserver")();
+  ShmVitalCounter* p_cnt_HA = shm.construct<ShmVitalCounter>("SHM_HealthAggregator")();
+  ShmVitalCounter* p_cnt_EH = shm.construct<ShmVitalCounter>("SHM_EmergencyHandler")();
+  ShmVitalCounter* p_cnt_TG = shm.construct<ShmVitalCounter>("SHM_TwistGate")();
+  ShmVitalCounter* p_cnt_YMC = shm.construct<ShmVitalCounter>("SHM_YMC_VehicleDriver")();
+  ShmVitalCounter* p_cnt_AS = shm.construct<ShmVitalCounter>("SHM_AS_VehicleDriver")();
+  bool* p_stopReq_DR = shm.construct<bool>("SHM_DRStopRequest")();
+
+  interprocess_mutex* p_mut_RO = shm.construct<interprocess_mutex>("MUT_RosObserver")();
+  interprocess_mutex* p_mut_HA = shm.construct<interprocess_mutex>("MUT_HealthAggregator")();
+  interprocess_mutex* p_mut_EH = shm.construct<interprocess_mutex>("MUT_EmergencyHandler")();
+  interprocess_mutex* p_mut_TG = shm.construct<interprocess_mutex>("MUT_TwistGate")();
+  interprocess_mutex* p_mut_YMC = shm.construct<interprocess_mutex>("MUT_YMC_VehicleDriver")();
+  interprocess_mutex* p_mut_AS = shm.construct<interprocess_mutex>("MUT_AS_VehicleDriver")();
+  interprocess_mutex* p_mut_DR = shm.construct<interprocess_mutex>("MUT_DRStopRequest")();
+
+  {
+    scoped_lock<interprocess_mutex> scpdlock_RO(*p_mut_RO);
+    p_cnt_RO->activated = true;
+    p_cnt_RO->thresh = (POLLING_INTERVAL_MSEC) * (SHM_TH_COUNTER_RO);
+    p_cnt_RO->value = 0;
+  }
+
+  while (!terminate_req_rcvd)
+  {
+    {
+      scoped_lock<interprocess_mutex> scpdlock_RO(*p_mut_RO);
+      scoped_lock<interprocess_mutex> scpdlock_HA(*p_mut_HA);
+      scoped_lock<interprocess_mutex> scpdlock_EH(*p_mut_EH);
+      scoped_lock<interprocess_mutex> scpdlock_TG(*p_mut_TG);
+      scoped_lock<interprocess_mutex> scpdlock_YMC(*p_mut_YMC);
+      scoped_lock<interprocess_mutex> scpdlock_AS(*p_mut_AS);
+      scoped_lock<interprocess_mutex> scpdlock_DR(*p_mut_DR);
+
+      p_cnt_RO->value = 0;
+      p_cnt_HA->value =
+          (p_cnt_HA->activated) ? std::min((p_cnt_HA->value + (POLLING_INTERVAL_MSEC)), SHM_COUNTER_MAX) : 0;
+      p_cnt_EH->value =
+          (p_cnt_EH->activated) ? std::min((p_cnt_EH->value + (POLLING_INTERVAL_MSEC)), SHM_COUNTER_MAX) : 0;
+      p_cnt_TG->value =
+          (p_cnt_TG->activated) ? std::min((p_cnt_TG->value + (POLLING_INTERVAL_MSEC)), SHM_COUNTER_MAX) : 0;
+      p_cnt_YMC->value =
+          (p_cnt_YMC->activated) ? std::min((p_cnt_YMC->value + (POLLING_INTERVAL_MSEC)), SHM_COUNTER_MAX) : 0;
+      p_cnt_AS->value =
+          (p_cnt_AS->activated) ? std::min((p_cnt_AS->value + (POLLING_INTERVAL_MSEC)), SHM_COUNTER_MAX) : 0;
+
+      static bool ros_error_detected_prev = false;
+      bool ros_error_detected = false;
+      std::string error_node;
+
+      if (p_cnt_HA->value > p_cnt_HA->thresh)
+      {
+        ros_error_detected = true;
+        error_node = "Health Aggregator";
+      }
+
+      if (p_cnt_EH->value > p_cnt_EH->thresh)
+      {
+        ros_error_detected = true;
+        error_node = "Emergency Handler";
+      }
+
+      if (p_cnt_TG->value > p_cnt_TG->thresh)
+      {
+        ros_error_detected = true;
+        error_node = "Twist Gate";
+      }
+
+      if (p_cnt_YMC->value > p_cnt_YMC->thresh)
+      {
+        ros_error_detected = true;
+        error_node = "YMC Vehicle Driver";
+      }
+
+      if (p_cnt_AS->value > p_cnt_AS->thresh)
+      {
+        ros_error_detected = true;
+        error_node = "AS Vehicle Driver";
+      }
+
+      if (ros_error_detected)
+      {
+        p_cnt_HA->modstatus = ModuleStatus::ErrorDetected;
+        if (!ros_error_detected_prev)
+        {
+          (*p_stopReq_DR) = true;
+        }
+
+        auto now = std::chrono::system_clock::now();
+        auto now_c = std::chrono::system_clock::to_time_t(now);
+        localtime_r(&now_c, &localtime);
+        std::cerr << "[START][TIME][LOCAL: " << std::put_time(&localtime, "%c") << "][" << error_node.c_str() << "]"
+                  << std::endl;
+      }
+      else
+      {
+        p_cnt_HA->modstatus = ModuleStatus::Normal;
+        if (ros_error_detected_prev)
+        {
+          (*p_stopReq_DR) = false;
+        }
+      }
+      ros_error_detected_prev = ros_error_detected;
+    }
+    usleep(POLLING_INTERVAL_USEC);
+  }
+
+  shared_memory_object::remove(SHM_NAME);
+
+  return 0;
+}

+ 257 - 0
src/ros/catkin/src/ros_observer/test/src/test_ros_observer.cpp

@@ -0,0 +1,257 @@
+/*
+ * Copyright 2019 Autoware Foundation. All rights reserved.
+ *
+ * Licensed under the Apache License, Version 2.0 (the "License");
+ * you may not use this file except in compliance with the License.
+ * You may obtain a copy of the License at
+ *
+ *     http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS,
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+ * See the License for the specific language governing permissions and
+ * limitations under the License.
+ *
+ */
+
+#include <ros/ros.h>
+#include <string>
+#include <gtest/gtest.h>
+#include <ros_observer/lib_ros_observer.h>
+
+using boost::interprocess::managed_shared_memory;
+using boost::interprocess::shared_memory_object;
+using boost::interprocess::scoped_lock;
+using boost::interprocess::create_only;
+using boost::interprocess::interprocess_mutex;
+
+class MyShmDRStopRequest : public ShmDRStopRequest
+{
+  friend class ShmTestSuite;
+
+public:
+  MyShmDRStopRequest(): ShmDRStopRequest() {}
+};
+
+class MyShmVitalMonitor : public ShmVitalMonitor
+{
+  friend class ShmTestSuite;
+
+public:
+  MyShmVitalMonitor(std::string name, const double rate, VitalMonitorMode mode = VitalMonitorMode::CNT_CLEAR):
+  ShmVitalMonitor(name, rate, mode) {}
+};
+
+class ShmTestSuite : public ::testing::Test
+{
+protected:
+  std::unique_ptr<MyShmVitalMonitor> myVMObj_;
+  std::unique_ptr<MyShmDRStopRequest> myDRObj_;
+
+  void setupVM(std::string name, const double rate, VitalMonitorMode mode = VitalMonitorMode::CNT_CLEAR)
+  {
+    myVMObj_ = std::unique_ptr<MyShmVitalMonitor>(new MyShmVitalMonitor(name, rate, mode));
+  }
+
+  void setupDR(void)
+  {
+    myDRObj_ = std::unique_ptr<MyShmDRStopRequest>(new MyShmDRStopRequest());
+  }
+
+public:
+  void modeTestVM(void)
+  {
+    ASSERT_EQ(myVMObj_->mode_, VitalMonitorMode::CNT_CLEAR);
+    myVMObj_->set_mode(VitalMonitorMode::CNT_MON);
+    ASSERT_EQ(myVMObj_->mode_, VitalMonitorMode::CNT_MON);
+  }
+
+  void nameTestVM(void)
+  {
+    ASSERT_EQ(myVMObj_->shm_name_, "SHM_NameTest");
+    ASSERT_EQ(myVMObj_->mut_name_, "MUT_NameTest");
+  }
+
+  void openTestVM(void)
+  {
+    EXPECT_FALSE(myVMObj_->attempt_to_open());
+
+    managed_shared_memory shm_new(create_only, SHM_NAME, SHM_SIZE);
+    ShmVitalCounter*  p_cnt_new = shm_new.construct<ShmVitalCounter>(myVMObj_->shm_name_.c_str())();
+    interprocess_mutex* p_mut_new = shm_new.construct<interprocess_mutex>(myVMObj_->mut_name_.c_str())();
+
+    ASSERT_TRUE(myVMObj_->attempt_to_open());
+
+    shared_memory_object::remove(SHM_NAME);
+  }
+
+  void runTestVM(void)
+  {
+    managed_shared_memory shm_new(create_only, SHM_NAME, SHM_SIZE);
+    ShmVitalCounter*  p_cnt_new = shm_new.construct<ShmVitalCounter>(myVMObj_->shm_name_.c_str())();
+    interprocess_mutex* p_mut_new = shm_new.construct<interprocess_mutex>(myVMObj_->mut_name_.c_str())();
+
+    myVMObj_->run();
+    ASSERT_TRUE(p_cnt_new->activated);
+
+    shared_memory_object::remove(SHM_NAME);
+  }
+
+  void updateTestVM(void)
+  {
+    managed_shared_memory shm_new(create_only, SHM_NAME, SHM_SIZE);
+    ShmVitalCounter*  p_cnt_new = shm_new.construct<ShmVitalCounter>(myVMObj_->shm_name_.c_str())();
+    interprocess_mutex* p_mut_new = shm_new.construct<interprocess_mutex>(myVMObj_->mut_name_.c_str())();
+
+    myVMObj_->mode_ = VitalMonitorMode::CNT_CLEAR;
+    p_cnt_new->activated = true;
+    p_cnt_new->value = 100;
+    myVMObj_->update_vital_counter();
+    ASSERT_EQ(p_cnt_new->value, 0);
+
+    myVMObj_->mode_ = VitalMonitorMode::CNT_MON;
+    myVMObj_->update_vital_counter();
+    ASSERT_EQ(p_cnt_new->value, myVMObj_->polling_interval_msec_);
+
+    p_cnt_new->value = SHM_COUNTER_MAX;
+    myVMObj_->update_vital_counter();
+    ASSERT_EQ(p_cnt_new->value, SHM_COUNTER_MAX);
+
+    p_cnt_new->value = p_cnt_new->thresh - 10;  /* 100hz */
+    myVMObj_->update_vital_counter();
+    ASSERT_EQ(p_cnt_new->modstatus, ModuleStatus::Normal);
+    myVMObj_->update_vital_counter();
+    ASSERT_EQ(p_cnt_new->modstatus, ModuleStatus::ErrorDetected);
+
+    shared_memory_object::remove(SHM_NAME);
+  }
+
+  void errorDetectionTestVM(void)
+  {
+    ASSERT_FALSE(myVMObj_->is_opened_);
+
+    managed_shared_memory shm_new(create_only, SHM_NAME, SHM_SIZE);
+    ShmVitalCounter*  p_cnt_new = shm_new.construct<ShmVitalCounter>(myVMObj_->shm_name_.c_str())();
+    interprocess_mutex* p_mut_new = shm_new.construct<interprocess_mutex>(myVMObj_->mut_name_.c_str())();
+
+    myVMObj_->run();
+    p_cnt_new->modstatus = ModuleStatus::Normal;
+    ASSERT_FALSE(myVMObj_->is_error_detected());
+    p_cnt_new->modstatus = ModuleStatus::ErrorDetected;
+    ASSERT_TRUE(myVMObj_->is_error_detected());
+
+    shared_memory_object::remove(SHM_NAME);
+  }
+
+  void openTestDR(void)
+  {
+    myDRObj_->is_opened_ = myDRObj_->attempt_to_open();
+    ASSERT_FALSE(myDRObj_->is_opened_);
+
+    managed_shared_memory shm_new(create_only, SHM_NAME, SHM_SIZE);
+    bool*  p_stop_request_new = shm_new.construct<bool>(myDRObj_->shm_name_.c_str())();
+    interprocess_mutex* p_mut_new = shm_new.construct<interprocess_mutex>(myDRObj_->mut_name_.c_str())();
+
+    myDRObj_->is_opened_ = myDRObj_->attempt_to_open();
+    ASSERT_TRUE(myDRObj_->is_opened_);
+
+    shared_memory_object::remove(SHM_NAME);
+  }
+
+  void clearTestDR(void)
+  {
+    managed_shared_memory shm_new(create_only, SHM_NAME, SHM_SIZE);
+    bool*  p_stop_request_new = shm_new.construct<bool>(myDRObj_->shm_name_.c_str())();
+    interprocess_mutex* p_mut_new = shm_new.construct<interprocess_mutex>(myDRObj_->mut_name_.c_str())();
+
+    (*p_stop_request_new) = false;
+    myDRObj_->clear_request();
+    ASSERT_FALSE((*p_stop_request_new));
+    (*p_stop_request_new) = true;
+    myDRObj_->clear_request();
+    ASSERT_FALSE((*p_stop_request_new));
+
+    shared_memory_object::remove(SHM_NAME);
+  }
+
+  void requestCheckTestDR(void)
+  {
+    managed_shared_memory shm_new(create_only, SHM_NAME, SHM_SIZE);
+    bool*  p_stop_request_new = shm_new.construct<bool>(myDRObj_->shm_name_.c_str())();
+    interprocess_mutex* p_mut_new = shm_new.construct<interprocess_mutex>(myDRObj_->mut_name_.c_str())();
+    bool is_request_received = false;
+
+    (*p_stop_request_new) = false;
+    is_request_received = myDRObj_->is_request_received();
+    ASSERT_FALSE(is_request_received);
+    (*p_stop_request_new) = true;
+    is_request_received = myDRObj_->is_request_received();
+    ASSERT_TRUE(is_request_received);
+
+    shared_memory_object::remove(SHM_NAME);
+  }
+};
+
+TEST_F(ShmTestSuite, ModeTestVM)
+{
+  setupVM("ModeTest", 100.0);
+  modeTestVM();
+}
+
+TEST_F(ShmTestSuite, NameTestVM)
+{
+  setupVM("NameTest", 100.0);
+  nameTestVM();
+}
+
+TEST_F(ShmTestSuite, OpenTestVM)
+{
+  setupVM("OpenTest", 100.0);
+  openTestVM();
+}
+
+TEST_F(ShmTestSuite, RunTestVM)
+{
+  setupVM("RunTest", 100.0);
+  runTestVM();
+}
+
+TEST_F(ShmTestSuite, UpdateTestVM)
+{
+  setupVM("UpdateTest", 100.0);
+  updateTestVM();
+}
+
+TEST_F(ShmTestSuite, ErrorDetectionTestVM)
+{
+  setupVM("ErrorDetectionTest", 100.0);
+  errorDetectionTestVM();
+}
+
+TEST_F(ShmTestSuite, OpenTestDR)
+{
+  setupDR();
+  openTestDR();
+}
+
+TEST_F(ShmTestSuite, ClearTestDR)
+{
+  setupDR();
+  clearTestDR();
+}
+
+TEST_F(ShmTestSuite, RequestCheckTestDR)
+{
+  setupDR();
+  requestCheckTestDR();
+}
+
+// Run all the tests that were declared with TEST()
+int main(int argc, char **argv)
+{
+  testing::InitGoogleTest(&argc, argv);
+  ros::init(argc, argv, "SharedMemoryMonitorTestNode");
+
+  return RUN_ALL_TESTS();
+}

+ 3 - 0
src/ros/catkin/src/ros_observer/test/test_ros_observer.test

@@ -0,0 +1,3 @@
+<launch>
+  <test test-name="test-ros_observer" pkg="ros_observer" type="test_ros_observer" name="test" />
+</launch>