diff --git a/march_launch/launch/march.launch b/march_launch/launch/march.launch index 037c15429..159d9d81d 100644 --- a/march_launch/launch/march.launch +++ b/march_launch/launch/march.launch @@ -9,6 +9,7 @@ + @@ -39,7 +40,7 @@ - + @@ -63,6 +64,7 @@ + diff --git a/march_launch/launch/march_simulation.launch b/march_launch/launch/march_simulation.launch index 7dda9820d..0633b54f7 100644 --- a/march_launch/launch/march_simulation.launch +++ b/march_launch/launch/march_simulation.launch @@ -6,6 +6,7 @@ + diff --git a/march_launch/package.xml b/march_launch/package.xml index 1977d96d0..d19d6c43e 100644 --- a/march_launch/package.xml +++ b/march_launch/package.xml @@ -20,7 +20,6 @@ march_gain_scheduling march_gait_selection march_safety - march_sound_scheduler march_state_machine xacro rosserial_python diff --git a/march_safety/CMakeLists.txt b/march_safety/CMakeLists.txt index 1945f1c4a..71bb7e6f1 100644 --- a/march_safety/CMakeLists.txt +++ b/march_safety/CMakeLists.txt @@ -7,6 +7,7 @@ find_package(catkin REQUIRED COMPONENTS march_shared_resources roscpp sensor_msgs + sound_play std_msgs urdf ) @@ -18,6 +19,7 @@ catkin_package( march_shared_resources roscpp sensor_msgs + sound_play std_msgs urdf ) @@ -47,7 +49,7 @@ install(TARGETS ${PROJECT_NAME} install(TARGETS ${PROJECT_NAME}_node RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} ) -install(DIRECTORY launch +install(DIRECTORY launch sound DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} ) diff --git a/march_safety/include/march_safety/input_device_safety.h b/march_safety/include/march_safety/input_device_safety.h index 90e20e29c..177b74ba1 100644 --- a/march_safety/include/march_safety/input_device_safety.h +++ b/march_safety/include/march_safety/input_device_safety.h @@ -21,7 +21,6 @@ class InputDeviceSafety : public SafetyType private: void inputDeviceAliveCallback(const std_msgs::TimeConstPtr& msg); - ros::NodeHandle n_; SafetyHandler* safety_handler_; ros::Duration connection_timeout_; ros::Time time_last_alive_; diff --git a/march_safety/include/march_safety/safety_handler.h b/march_safety/include/march_safety/safety_handler.h index 19f866c9d..4e338d10a 100644 --- a/march_safety/include/march_safety/safety_handler.h +++ b/march_safety/include/march_safety/safety_handler.h @@ -4,31 +4,32 @@ #include #include +#include + #include -#include #include class SafetyHandler { public: - SafetyHandler(ros::NodeHandle* n, ros::Publisher* error_publisher, ros::Publisher* sound_publisher, - ros::Publisher* gait_instruction_publisher); + SafetyHandler(ros::NodeHandle* n, ros::Publisher* error_publisher, ros::Publisher* gait_instruction_publisher, + sound_play::SoundClient& sound_client); - void publishFatal(std::string message); + void publishFatal(const std::string& message); - void publishNonFatal(std::string message); + void publishNonFatal(const std::string& message); void publishErrorMessage(const std::string& message, int8_t error_type) const; void publishStopMessage() const; - void publishErrorSound(int8_t error_type) const; - private: ros::NodeHandle* n_; ros::Publisher* error_publisher_; - ros::Publisher* sound_publisher_; ros::Publisher* gait_instruction_publisher_; + + sound_play::Sound fatal_sound_; + sound_play::Sound non_fatal_sound_; }; #endif // MARCH_SAFETY_SAFETY_HANDLER_H diff --git a/march_safety/include/march_safety/temperature_safety.h b/march_safety/include/march_safety/temperature_safety.h index 1604a2384..a537904db 100644 --- a/march_safety/include/march_safety/temperature_safety.h +++ b/march_safety/include/march_safety/temperature_safety.h @@ -10,7 +10,6 @@ #include #include -#include #include "march_safety/safety_type.h" #include "march_safety/safety_handler.h" diff --git a/march_safety/package.xml b/march_safety/package.xml index 4ff656163..d8eda715d 100644 --- a/march_safety/package.xml +++ b/march_safety/package.xml @@ -16,6 +16,7 @@ sensor_msgs std_msgs urdf + sound_play rostest code_coverage diff --git a/march_sound_scheduler/sound/fatal.wav b/march_safety/sound/fatal.wav similarity index 100% rename from march_sound_scheduler/sound/fatal.wav rename to march_safety/sound/fatal.wav diff --git a/march_sound_scheduler/sound/non-fatal.wav b/march_safety/sound/non_fatal.wav similarity index 100% rename from march_sound_scheduler/sound/non-fatal.wav rename to march_safety/sound/non_fatal.wav diff --git a/march_safety/src/input_device_safety.cpp b/march_safety/src/input_device_safety.cpp index 9ff827c07..9ed84ec94 100644 --- a/march_safety/src/input_device_safety.cpp +++ b/march_safety/src/input_device_safety.cpp @@ -7,7 +7,7 @@ InputDeviceSafety::InputDeviceSafety(ros::NodeHandle* n, SafetyHandler* safety_h { int milliseconds; ros::param::get("~input_device_connection_timeout", milliseconds); - double send_errors_interval_param; + int send_errors_interval_param; ros::param::get("~send_errors_interval", send_errors_interval_param); this->send_errors_interval_ = send_errors_interval_param; this->connection_timeout_ = ros::Duration(milliseconds / 1000.0); diff --git a/march_safety/src/safety_handler.cpp b/march_safety/src/safety_handler.cpp index d711741b3..2f538479e 100644 --- a/march_safety/src/safety_handler.cpp +++ b/march_safety/src/safety_handler.cpp @@ -3,12 +3,13 @@ #include -SafetyHandler::SafetyHandler(ros::NodeHandle* n, ros::Publisher* error_publisher, ros::Publisher* sound_publisher, - ros::Publisher* gait_instruction_publisher) +SafetyHandler::SafetyHandler(ros::NodeHandle* n, ros::Publisher* error_publisher, + ros::Publisher* gait_instruction_publisher, sound_play::SoundClient& sound_client) : n_(n) , error_publisher_(error_publisher) - , sound_publisher_(sound_publisher) , gait_instruction_publisher_(gait_instruction_publisher) + , fatal_sound_(sound_client.waveSoundFromPkg("march_safety", "sound/fatal.wav")) + , non_fatal_sound_(sound_client.waveSoundFromPkg("march_safety", "sound/non_fatal.wav")) { } @@ -30,35 +31,19 @@ void SafetyHandler::publishStopMessage() const this->gait_instruction_publisher_->publish(gait_instruction_msg); } -void SafetyHandler::publishErrorSound(int8_t error_type) const -{ - march_shared_resources::Sound sound; - sound.header.stamp = ros::Time::now(); - sound.time = ros::Time::now(); - if (error_type == march_shared_resources::Error::FATAL) - { - sound.file_name = "fatal.wav"; - } - else if (error_type == march_shared_resources::Error::NON_FATAL) - { - sound.file_name = "non-fatal.wav"; - } - this->sound_publisher_->publish(sound); -} - -void SafetyHandler::publishFatal(std::string message) +void SafetyHandler::publishFatal(const std::string& message) { ROS_ERROR("%s", message.c_str()); this->publishErrorMessage(message, march_shared_resources::Error::FATAL); - this->publishErrorSound(march_shared_resources::Error::FATAL); + this->non_fatal_sound_.play(); } -void SafetyHandler::publishNonFatal(std::string message) +void SafetyHandler::publishNonFatal(const std::string& message) { ROS_ERROR("%s", message.c_str()); this->publishStopMessage(); this->publishErrorMessage(message, march_shared_resources::Error::NON_FATAL); - this->publishErrorSound(march_shared_resources::Error::NON_FATAL); + this->non_fatal_sound_.play(); } diff --git a/march_safety/src/safety_node.cpp b/march_safety/src/safety_node.cpp index b03b16cc0..42a9886b0 100644 --- a/march_safety/src/safety_node.cpp +++ b/march_safety/src/safety_node.cpp @@ -1,21 +1,16 @@ // Copyright 2018 Project March. -#include #include #include #include -#include -#include -#include -#include +#include #include "march_shared_resources/Error.h" -#include "march_shared_resources/Sound.h" #include "march_shared_resources/GaitInstruction.h" #include "march_safety/input_device_safety.h" -#include "march_safety/temperature_safety.h" #include "march_safety/safety_handler.h" +#include "march_safety/temperature_safety.h" int main(int argc, char** argv) { @@ -36,11 +31,11 @@ int main(int argc, char** argv) // Create an error publisher to notify the system (state machine) if something is wrong ros::Publisher error_publisher = n.advertise("/march/error", 1000); - ros::Publisher sound_publisher = n.advertise("/march/sound/schedule", 1000); ros::Publisher gait_instruction_publisher = n.advertise("/march/input_device/instruction", 1000); + sound_play::SoundClient sound_client(n, "robotsound"); - SafetyHandler safety_handler = SafetyHandler(&n, &error_publisher, &sound_publisher, &gait_instruction_publisher); + SafetyHandler safety_handler = SafetyHandler(&n, &error_publisher, &gait_instruction_publisher, sound_client); std::vector> safety_list; safety_list.push_back(std::unique_ptr(new TemperatureSafety(&n, &safety_handler, joint_names))); diff --git a/march_safety/src/temperature_safety.cpp b/march_safety/src/temperature_safety.cpp index 885341bdb..c61a5ff7a 100644 --- a/march_safety/src/temperature_safety.cpp +++ b/march_safety/src/temperature_safety.cpp @@ -9,7 +9,7 @@ TemperatureSafety::TemperatureSafety(ros::NodeHandle* n, SafetyHandler* safety_handler, std::vector joint_names) - : n_(n), safety_handler_(safety_handler), joint_names_(joint_names) + : n_(n), safety_handler_(safety_handler), joint_names_(std::move(joint_names)) { ros::param::get("~default_temperature_threshold", this->default_temperature_threshold_); ros::param::get("~temperature_thresholds_warning", this->warning_temperature_thresholds_map_); diff --git a/march_shared_resources/CMakeLists.txt b/march_shared_resources/CMakeLists.txt index acd9e5048..a5ba46ccc 100644 --- a/march_shared_resources/CMakeLists.txt +++ b/march_shared_resources/CMakeLists.txt @@ -21,7 +21,6 @@ add_message_files( LowVoltageNet.msg PowerDistributionBoardState.msg Setpoint.msg - Sound.msg Subgait.msg ) diff --git a/march_shared_resources/msg/GaitInstruction.msg b/march_shared_resources/msg/GaitInstruction.msg index e8227af32..9e9adbf4c 100644 --- a/march_shared_resources/msg/GaitInstruction.msg +++ b/march_shared_resources/msg/GaitInstruction.msg @@ -8,6 +8,9 @@ int8 STOP = 0 int8 GAIT = 1 int8 PAUSE = 2 int8 CONTINUE = 3 +int8 INCREMENT_STEP_SIZE = 4 +int8 DECREMENT_STEP_SIZE = 5 # If the type is a GAIT this is the name of the gait. string gait_name + diff --git a/march_shared_resources/msg/Sound.msg b/march_shared_resources/msg/Sound.msg deleted file mode 100644 index b3a93a4fa..000000000 --- a/march_shared_resources/msg/Sound.msg +++ /dev/null @@ -1,3 +0,0 @@ -Header header -time time -string file_name diff --git a/march_shared_resources/msg/Subgait.msg b/march_shared_resources/msg/Subgait.msg index 92e86cad4..fed12bcbf 100644 --- a/march_shared_resources/msg/Subgait.msg +++ b/march_shared_resources/msg/Subgait.msg @@ -9,4 +9,4 @@ Setpoint[] setpoints trajectory_msgs/JointTrajectory trajectory duration duration -Sound[] sounds +string[] sounds diff --git a/march_sound_scheduler/CMakeLists.txt b/march_sound_scheduler/CMakeLists.txt deleted file mode 100644 index 61d0bad83..000000000 --- a/march_sound_scheduler/CMakeLists.txt +++ /dev/null @@ -1,47 +0,0 @@ -cmake_minimum_required(VERSION 2.8.3) -project(march_sound_scheduler) -add_compile_options(-std=c++11 -Wall -Wextra) - -find_package(catkin REQUIRED COMPONENTS - march_shared_resources - roscpp - sound_play -) - -catkin_package( - INCLUDE_DIRS include - LIBRARIES ${PROJECT_NAME} - CATKIN_DEPENDS - march_shared_resources - roscpp - sound_play -) - -include_directories( - include - ${catkin_INCLUDE_DIRS} -) - -add_library(${PROJECT_NAME} - src/scheduled_sound.cpp - src/scheduler.cpp -) - -target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES}) - -add_executable(${PROJECT_NAME}_node src/sound_scheduler_node.cpp) -target_link_libraries(${PROJECT_NAME}_node ${PROJECT_NAME}) -add_dependencies(${PROJECT_NAME}_node ${catkin_EXPORTED_TARGETS}) - -install(DIRECTORY include/${PROJECT_NAME} - DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} -) -install(TARGETS ${PROJECT_NAME} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} -) -install(TARGETS ${PROJECT_NAME}_node - RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} -) -install(DIRECTORY launch sound - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} -) diff --git a/march_sound_scheduler/include/march_sound_scheduler/scheduled_sound.h b/march_sound_scheduler/include/march_sound_scheduler/scheduled_sound.h deleted file mode 100644 index f387b2ac8..000000000 --- a/march_sound_scheduler/include/march_sound_scheduler/scheduled_sound.h +++ /dev/null @@ -1,29 +0,0 @@ -// Copyright 2019 Project March. -#ifndef MARCH_SOUND_SCHEDULER_SCHEDULED_SOUND_H -#define MARCH_SOUND_SCHEDULER_SCHEDULED_SOUND_H -#include - -#include -#include - -class ScheduledSound -{ -public: - ros::Time time; - std::string sound; - - ScheduledSound(const ros::Time& time, const std::string& sound); - - friend bool operator<(const ScheduledSound& lhs, const ScheduledSound& rhs) - { - return lhs.time > rhs.time; - } - - /** @brief Override stream operator for clean printing */ - friend ::std::ostream& operator<<(std::ostream& os, const ScheduledSound& scheduled_sound) - { - return os << scheduled_sound.sound << " in " << (scheduled_sound.time - ros::Time::now()) << "s"; - } -}; - -#endif // MARCH_SOUND_SCHEDULER_SCHEDULED_SOUND_H diff --git a/march_sound_scheduler/include/march_sound_scheduler/scheduler.h b/march_sound_scheduler/include/march_sound_scheduler/scheduler.h deleted file mode 100644 index ef394d253..000000000 --- a/march_sound_scheduler/include/march_sound_scheduler/scheduler.h +++ /dev/null @@ -1,34 +0,0 @@ -// Copyright 2019 Project March. -#ifndef MARCH_SOUND_SCHEDULER_SCHEDULER_H -#define MARCH_SOUND_SCHEDULER_SCHEDULER_H - -#include -#include - -#include -#include - -#include - -#include - -#include "march_sound_scheduler/scheduled_sound.h" - -class Scheduler -{ -public: - Scheduler(); - - void schedule(ScheduledSound sound); - void scheduleMsg(march_shared_resources::Sound msg); - - void spin(); - - void play(ScheduledSound sound); - -private: - std::priority_queue> sound_queue_; - sound_play::SoundClient sc_; -}; - -#endif // MARCH_SOUND_SCHEDULER_SCHEDULER_H diff --git a/march_sound_scheduler/launch/march_sound_scheduler.launch b/march_sound_scheduler/launch/march_sound_scheduler.launch deleted file mode 100644 index 15e4ed607..000000000 --- a/march_sound_scheduler/launch/march_sound_scheduler.launch +++ /dev/null @@ -1,4 +0,0 @@ - - - - diff --git a/march_sound_scheduler/package.xml b/march_sound_scheduler/package.xml deleted file mode 100644 index 7fa8fba72..000000000 --- a/march_sound_scheduler/package.xml +++ /dev/null @@ -1,14 +0,0 @@ - - - march_sound_scheduler - 0.0.0 - Schedules and plays sound with the ros sound_play package - Project March - TODO - - catkin - - roscpp - march_shared_resources - sound_play - diff --git a/march_sound_scheduler/src/scheduled_sound.cpp b/march_sound_scheduler/src/scheduled_sound.cpp deleted file mode 100644 index 8b77812c5..000000000 --- a/march_sound_scheduler/src/scheduled_sound.cpp +++ /dev/null @@ -1,10 +0,0 @@ -// Copyright 2018 Project March. -#include - -#include - -#include "march_sound_scheduler/scheduled_sound.h" - -ScheduledSound::ScheduledSound(const ros::Time& time, const std::string& sound) : time(time), sound(sound) -{ -} diff --git a/march_sound_scheduler/src/scheduler.cpp b/march_sound_scheduler/src/scheduler.cpp deleted file mode 100644 index 91691f190..000000000 --- a/march_sound_scheduler/src/scheduler.cpp +++ /dev/null @@ -1,40 +0,0 @@ -// Copyright 2019 Project March. -#include "march_sound_scheduler/scheduler.h" -#include "march_sound_scheduler/scheduled_sound.h" - -Scheduler::Scheduler() -{ -} - -void Scheduler::schedule(ScheduledSound sound) -{ - this->sound_queue_.push(sound); -} - -void Scheduler::scheduleMsg(march_shared_resources::Sound msg) -{ - ROS_DEBUG("Received request to schedule sound %s at time %f", msg.file_name.c_str(), msg.time.toSec()); - this->schedule(ScheduledSound(msg.time, msg.file_name)); -} - -void Scheduler::spin() -{ - if (this->sound_queue_.empty()) - { - ROS_DEBUG("Sounds in queue %ld", this->sound_queue_.size()); - return; - } - - ROS_DEBUG_STREAM("Next sound: " << this->sound_queue_.top()); - - if (this->sound_queue_.top().time <= ros::Time::now()) - { - this->play(this->sound_queue_.top()); - this->sound_queue_.pop(); - } -} - -void Scheduler::play(ScheduledSound sound) -{ - this->sc_.playWaveFromPkg("march_sound_scheduler", "sound/" + sound.sound); -} diff --git a/march_sound_scheduler/src/sound_scheduler_node.cpp b/march_sound_scheduler/src/sound_scheduler_node.cpp deleted file mode 100644 index 243102164..000000000 --- a/march_sound_scheduler/src/sound_scheduler_node.cpp +++ /dev/null @@ -1,32 +0,0 @@ -// Copyright 2018 Project March. -#include - -#include "march_sound_scheduler/scheduler.h" - -int main(int argc, char** argv) -{ - ros::init(argc, argv, "march_sound_scheduler"); - ros::NodeHandle n; - - ros::Publisher sound_pub = n.advertise("robotsound", 0); - - while (ros::ok() && sound_pub.getNumSubscribers() == 0) - { - ROS_DEBUG("Waiting on sound play topic"); - ros::Duration(0.1).sleep(); - } - - Scheduler scheduler; - - ros::Subscriber sound_sub = n.subscribe("/march/sound/schedule", 10, &Scheduler::scheduleMsg, &scheduler); - - ros::Rate rate(10); - while (ros::ok()) - { - scheduler.spin(); - ros::spinOnce(); - rate.sleep(); - } - - return 0; -}