diff --git a/piksi_multi_cpp/CMakeLists.txt b/piksi_multi_cpp/CMakeLists.txt index 113883f3..7bd9f125 100644 --- a/piksi_multi_cpp/CMakeLists.txt +++ b/piksi_multi_cpp/CMakeLists.txt @@ -38,7 +38,6 @@ cs_add_library(${PROJECT_NAME} src/sbp_callback_handler/ros_time_handler.cc src/sbp_callback_handler/sbp_callback_handler.cc src/sbp_callback_handler/sbp_callback_handler_factory.cc - src/sbp_callback_handler/sbp_observation_callback_handler.cc ) target_link_libraries(${PROJECT_NAME} serialport stdc++fs) diff --git a/piksi_multi_cpp/include/piksi_multi_cpp/observations/callback_observation_interface.h b/piksi_multi_cpp/include/piksi_multi_cpp/observations/callback_observation_interface.h index 33621cd7..21f21cce 100644 --- a/piksi_multi_cpp/include/piksi_multi_cpp/observations/callback_observation_interface.h +++ b/piksi_multi_cpp/include/piksi_multi_cpp/observations/callback_observation_interface.h @@ -10,6 +10,7 @@ namespace piksi_multi_cpp { /* * Interface for a class that can handle observation callbacks * from SBP. + * More message callbacks can be added here. */ class CallbackObservationInterface { public: @@ -18,6 +19,9 @@ class CallbackObservationInterface { virtual void observationCallback(msg_glo_biases_t msg) = 0; virtual void observationCallback(msg_obs_t_var msg) = 0; virtual void observationCallback(msg_heartbeat_t msg) = 0; + virtual void observationCallback(msg_ephemeris_gps_t msg) = 0; + virtual void observationCallback(msg_ephemeris_glo_t msg) = 0; + virtual void observationCallback(msg_iono_t msg) = 0; }; } // namespace piksi_multi_cpp diff --git a/piksi_multi_cpp/include/piksi_multi_cpp/observations/cb_to_raw_obs_converter.h b/piksi_multi_cpp/include/piksi_multi_cpp/observations/cb_to_raw_obs_converter.h index ab1e1cbe..c88d2689 100644 --- a/piksi_multi_cpp/include/piksi_multi_cpp/observations/cb_to_raw_obs_converter.h +++ b/piksi_multi_cpp/include/piksi_multi_cpp/observations/cb_to_raw_obs_converter.h @@ -28,6 +28,9 @@ class CBtoRawObsConverter : public CallbackObservationInterface { void observationCallback(msg_glo_biases_t msg) final; void observationCallback(msg_obs_t_var msg) final; void observationCallback(msg_heartbeat_t msg) final; + void observationCallback(msg_ephemeris_gps_t msg) final; + void observationCallback(msg_ephemeris_glo_t msg) final; + void observationCallback(msg_iono_t msg) final; static std::shared_ptr createFor( const RawObservationInterface::Ptr& consumer, const uint16_t sbp_sender_id) { diff --git a/piksi_multi_cpp/include/piksi_multi_cpp/observations/file_observation_logger.h b/piksi_multi_cpp/include/piksi_multi_cpp/observations/file_observation_logger.h index 1d2dd149..c4171d59 100644 --- a/piksi_multi_cpp/include/piksi_multi_cpp/observations/file_observation_logger.h +++ b/piksi_multi_cpp/include/piksi_multi_cpp/observations/file_observation_logger.h @@ -2,28 +2,52 @@ #define PIKSI_MULTI_CPP_OBSERVATIONS_FILE_OBSERVATION_LOGGER_H_ #include +#include namespace piksi_multi_cpp { /* - * Logger that writes Raw observations into file such that it can be used - * for ppk. - * - * Consumes Raw Observations, thus has interface RawObservationInterface + * Logger that writes raw observations into file such that it can be used + * for PPK. + * Logger consumes raw observations. */ class FileObservationLogger : public RawObservationInterface { public: FileObservationLogger() {} + /** + * Creates and opens log file. In case file name already exists a number is + * appended to filename so that old files are not overwritten. + */ bool open(const std::string& filename); + + /** + * Close log file + */ void close(); + + /** + * Return status whether logger is currently running + */ + bool isLogging(); + + /** + * Write observations to binary file + */ void insertObservation(const RawObservation& data) final; + + /** + * Destructor making sure log file is closed. + */ ~FileObservationLogger(); private: + // File pointer. FILE* log_file_{nullptr}; // not using fstream, but raw file for performance. - // File pointer etc. + // mutex to lock file when writing + std::mutex file_mtx_; }; + } // namespace piksi_multi_cpp #endif // PIKSI_MULTI_CPP_OBSERVATIONS_FILE_OBSERVATION_LOGGER_H_ diff --git a/piksi_multi_cpp/include/piksi_multi_cpp/receiver/receiver_base_station.h b/piksi_multi_cpp/include/piksi_multi_cpp/receiver/receiver_base_station.h index d12d5371..3f2b704d 100644 --- a/piksi_multi_cpp/include/piksi_multi_cpp/receiver/receiver_base_station.h +++ b/piksi_multi_cpp/include/piksi_multi_cpp/receiver/receiver_base_station.h @@ -25,7 +25,6 @@ class ReceiverBaseStation : public ReceiverRos { const piksi_rtk_msgs::PositionWithCovarianceStamped::Ptr& msg); void setupBaseStationSampling(); - uint16_t sbp_sender_id_ {0x42}; ros::ServiceServer resample_base_position_srv_; ros::Subscriber ml_estimate_sub_; ros::Subscriber receiver_state_sub_; diff --git a/piksi_multi_cpp/include/piksi_multi_cpp/receiver/receiver_ros.h b/piksi_multi_cpp/include/piksi_multi_cpp/receiver/receiver_ros.h index 599d95f6..30149e1d 100644 --- a/piksi_multi_cpp/include/piksi_multi_cpp/receiver/receiver_ros.h +++ b/piksi_multi_cpp/include/piksi_multi_cpp/receiver/receiver_ros.h @@ -2,14 +2,17 @@ #define PIKSI_MULTI_CPP_RECEIVER_RECEIVER_ROS_H_ #include +#include #include #include #include #include +#include "piksi_multi_cpp/observations/file_observation_logger.h" #include "piksi_multi_cpp/receiver/settings_io.h" #include "piksi_multi_cpp/sbp_callback_handler/geotf_handler.h" #include "piksi_multi_cpp/sbp_callback_handler/position_sampler.h" #include "piksi_multi_cpp/sbp_callback_handler/sbp_callback_handler.h" +#include "piksi_multi_cpp/sbp_callback_handler/sbp_ephemeris_callback_handler.h" #include "piksi_multi_cpp/sbp_callback_handler/sbp_observation_callback_handler.h" namespace piksi_multi_cpp { @@ -21,12 +24,33 @@ class ReceiverRos : public SettingsIo { ReceiverRos(const ros::NodeHandle& nh, const Device::Ptr& device); + // set up user ID + bool init() override; + + /** + * Set up File Logger. + * Per default observations are stored in .ros with current date & time + * prefixed with "_", therefore multiple receivers store + * observations into different files. + */ + bool startFileLogger(); + + // ROS service to start/stop logger + bool startStopFileLoggerCallback(std_srvs::SetBool::Request& req, + std_srvs::SetBool::Response& res); + protected: // ROS node handle in the correct receiver namespace. ros::NodeHandle nh_; + // Service Server for starting or stopping file logger + ros::ServiceServer start_stop_logger_srv_; - // Observation callbackhandlers + // Sender ID of device + uint16_t sbp_sender_id_{0x42}; + + // Observation & Ephemeris callbackhandlers std::unique_ptr obs_cbs_; + std::unique_ptr eph_cbs_; // get vector valued string params std::vector getVectorParam( @@ -36,8 +60,12 @@ class ReceiverRos : public SettingsIo { GeoTfHandler::Ptr geotf_handler_; // Averages the position over multiple ECEF messages. PositionSampler::Ptr position_sampler_; + // File logger object + std::shared_ptr obs_logger_; private: + void initObsLogger(); + // Relaying all SBP messages. Common for all receivers. std::vector sbp_relays_; // Relaying all ROS messages. Common for all receivers. diff --git a/piksi_multi_cpp/include/piksi_multi_cpp/sbp_callback_handler/sbp_ephemeris_callback_handler.h b/piksi_multi_cpp/include/piksi_multi_cpp/sbp_callback_handler/sbp_ephemeris_callback_handler.h new file mode 100644 index 00000000..b6fda39a --- /dev/null +++ b/piksi_multi_cpp/include/piksi_multi_cpp/sbp_callback_handler/sbp_ephemeris_callback_handler.h @@ -0,0 +1,37 @@ +#ifndef PIKSI_MULTI_CPP_SBP_CALLBACK_HANDLER_SBP_EPHEMERIS_CALLBACK_HANDLER_H_ +#define PIKSI_MULTI_CPP_SBP_CALLBACK_HANDLER_SBP_EPHEMERIS_CALLBACK_HANDLER_H_ +#include +#include +#include + +namespace piksi_multi_cpp { + +/* + * Subscribes to all 3 observation type callbacks simultaneously using + * LambdaCallbackHandlers and redirects these messages to all registered + * listeners. + * + */ +class SBPEphemerisCallbackHandler + : public SBPMsgTypeCallbackHandler { + public: + SBPEphemerisCallbackHandler(const ros::NodeHandle nh, + const std::shared_ptr& state) + : SBPMsgTypeCallbackHandler(nh, state), + gps_ephemeris_handler_{getCallback(), + SBP_MSG_EPHEMERIS_GPS, state}, + glo_ephemeris_handler_{getCallback(), SBP_MSG_EPHEMERIS_GLO, + state}, + iono_delay_handler_{getCallback(), SBP_MSG_IONO, state} {}; + + private: + /* Set up Lambda redirect callbacks for the three message types used for + * converting sbp to rinex, such that this class gets any of the three callbacks and can + * forward them to the observation listeners */ + SBPLambdaCallbackHandler gps_ephemeris_handler_; + SBPLambdaCallbackHandler glo_ephemeris_handler_; + SBPLambdaCallbackHandler iono_delay_handler_; +}; +} // namespace piksi_multi_cpp + +#endif diff --git a/piksi_multi_cpp/include/piksi_multi_cpp/sbp_callback_handler/sbp_msg_type_callback_handler.h b/piksi_multi_cpp/include/piksi_multi_cpp/sbp_callback_handler/sbp_msg_type_callback_handler.h new file mode 100644 index 00000000..d65e452b --- /dev/null +++ b/piksi_multi_cpp/include/piksi_multi_cpp/sbp_callback_handler/sbp_msg_type_callback_handler.h @@ -0,0 +1,60 @@ +#ifndef PIKSI_MULTI_CPP_SBP_CALLBACK_HANDLER_SBP_OBS_TYPE_CALLBACK_HANDLER_H_ +#define PIKSI_MULTI_CPP_SBP_CALLBACK_HANDLER_SBP_OBS_TYPE_CALLBACK_HANDLER_H_ +#include +#include +#include +#include + +namespace piksi_multi_cpp { +namespace s = std::placeholders; + +class SBPMsgTypeCallbackHandler { + + public: + SBPMsgTypeCallbackHandler(const ros::NodeHandle nh, + const std::shared_ptr& state) + : state_(state){}; + + /* + * Add listeners to message callbacks. + */ + void addObservationCallbackListener(const CallbackObservationInterface::Ptr& listener) { + if (listener.get()) { + listeners_.push_back(listener); + } + } + + protected: + /* + * Convenience method to create a std::function for the callbackToListeners + * method. + * Implemented in header because of template. + */ + template + std::function getCallback() { + return std::bind( + &SBPMsgTypeCallbackHandler::callbackToListeners, this, + s::_1, s::_2); + } + + /* + * Forwards messages to observation listeners. + * Important: Only compiles if it is used only for sbp messages that can be + * consumed by the listeners, i.e. that have a viable observationCallback + * overload + * Implemented in header because of template. + */ + template + void callbackToListeners(const SBPMsgStruct& msg, const uint8_t len) { + // trigger callback on all listeners + for (const auto& listener : listeners_) { + listener->observationCallback(msg); + } + } + + std::shared_ptr state_; + std::vector listeners_{}; +}; +} // namespace piksi_multi_cpp + +#endif diff --git a/piksi_multi_cpp/include/piksi_multi_cpp/sbp_callback_handler/sbp_observation_callback_handler.h b/piksi_multi_cpp/include/piksi_multi_cpp/sbp_callback_handler/sbp_observation_callback_handler.h index 43ce7dbf..c7a135a9 100644 --- a/piksi_multi_cpp/include/piksi_multi_cpp/sbp_callback_handler/sbp_observation_callback_handler.h +++ b/piksi_multi_cpp/include/piksi_multi_cpp/sbp_callback_handler/sbp_observation_callback_handler.h @@ -1,17 +1,10 @@ #ifndef PIKSI_MULTI_CPP_SBP_CALLBACK_HANDLER_SBP_OBSERVATION_CALLBACK_HANDLER_H_ #define PIKSI_MULTI_CPP_SBP_CALLBACK_HANDLER_SBP_OBSERVATION_CALLBACK_HANDLER_H_ -#include -#include -#include -#include -#include #include +#include #include -#include -#include namespace piksi_multi_cpp { -namespace s = std::placeholders; /* * Subscribes to all 4 observation type callbacks simultaneously using @@ -19,44 +12,21 @@ namespace s = std::placeholders; * listeners. * */ -class SBPObservationCallbackHandler { +class SBPObservationCallbackHandler + : public SBPMsgTypeCallbackHandler { public: SBPObservationCallbackHandler(const ros::NodeHandle nh, - const std::shared_ptr& state); - - void addObservationCallbackListener( - const CallbackObservationInterface::Ptr& listener); + const std::shared_ptr& state) + : SBPMsgTypeCallbackHandler(nh, state), + base_pos_handler_{getCallback(), + SBP_MSG_BASE_POS_ECEF, state}, + glo_bias_handler_{getCallback(), SBP_MSG_GLO_BIASES, + state}, + obs_handler_{getCallback(), SBP_MSG_OBS, state}, + heartbeat_handler_{getCallback(), SBP_MSG_HEARTBEAT, + state} {}; private: - /* - * Convenience method to create a std::function for the callbackToListeners - * method. - * Implemented in header because of template. - */ - template - std::function getCallback() { - return std::bind( - &SBPObservationCallbackHandler::callbackToListeners, this, - s::_1, s::_2); - } - - /* - * Forwards messages to observation listeners. - * Important: Only compiles if it is used only for sbp messages that can be - * consumed by the listeners, i.e. that have a viable observationCallback - * overload - * Implemented in header because of template. - */ - template - void callbackToListeners(const SBPMsgStruct& msg, const uint8_t len) { - // trigger callback on all listeners - for (const auto& listener : listeners_) { - listener->observationCallback(msg); - } - } - - std::shared_ptr state_; - std::vector listeners_{}; /* Set up Lambda redirect callbacks for the four message types used for * corrections, such that this class gets any of the four callbacks and can * forward them to the observation listeners */ diff --git a/piksi_multi_cpp/launch/base.launch b/piksi_multi_cpp/launch/base.launch index 98926e22..739da388 100644 --- a/piksi_multi_cpp/launch/base.launch +++ b/piksi_multi_cpp/launch/base.launch @@ -5,6 +5,9 @@ + + + diff --git a/piksi_multi_cpp/launch/rover.launch b/piksi_multi_cpp/launch/rover.launch index 210847ff..75bd4ff7 100644 --- a/piksi_multi_cpp/launch/rover.launch +++ b/piksi_multi_cpp/launch/rover.launch @@ -4,17 +4,20 @@ - + + + + - - + + diff --git a/piksi_multi_cpp/src/observations/cb_to_raw_obs_converter.cc b/piksi_multi_cpp/src/observations/cb_to_raw_obs_converter.cc index 1ea63eaa..a032d343 100644 --- a/piksi_multi_cpp/src/observations/cb_to_raw_obs_converter.cc +++ b/piksi_multi_cpp/src/observations/cb_to_raw_obs_converter.cc @@ -53,6 +53,36 @@ void CBtoRawObsConverter::observationCallback(msg_heartbeat_t msg) { finishMessage(); } +void CBtoRawObsConverter::observationCallback(msg_ephemeris_gps_t msg) { + // Repack into full SBP Message + startMessage(); + sbp_send_message(&sbp_state_, SBP_MSG_EPHEMERIS_GPS, sbp_sender_id_, sizeof(msg), + reinterpret_cast(&msg), + &CBtoRawObsConverter::sbp_write_redirect); + // this triggers sbp_write_redirect + finishMessage(); +} + +void CBtoRawObsConverter::observationCallback(msg_ephemeris_glo_t msg) { + // Repack into full SBP Message + startMessage(); + sbp_send_message(&sbp_state_, SBP_MSG_EPHEMERIS_GLO, sbp_sender_id_, sizeof(msg), + reinterpret_cast(&msg), + &CBtoRawObsConverter::sbp_write_redirect); + // this triggers sbp_write_redirect + finishMessage(); +} + +void CBtoRawObsConverter::observationCallback(msg_iono_t msg) { + // Repack into full SBP Message + startMessage(); + sbp_send_message(&sbp_state_, SBP_MSG_IONO, sbp_sender_id_, sizeof(msg), + reinterpret_cast(&msg), + &CBtoRawObsConverter::sbp_write_redirect); + // this triggers sbp_write_redirect + finishMessage(); +} + void CBtoRawObsConverter::startMessage() { buffer_msg_.clear(); } void CBtoRawObsConverter::finishMessage() { diff --git a/piksi_multi_cpp/src/observations/file_observation_logger.cc b/piksi_multi_cpp/src/observations/file_observation_logger.cc index 19f222bb..d8f1007c 100644 --- a/piksi_multi_cpp/src/observations/file_observation_logger.cc +++ b/piksi_multi_cpp/src/observations/file_observation_logger.cc @@ -4,27 +4,39 @@ namespace piksi_multi_cpp { bool FileObservationLogger::open(const std::string& filename) { if (log_file_ != nullptr) return false; // can't open if another one is open. - log_file_ = fopen(filename.c_str(), "wb"); // open binary file. + int file_number = 0; + std::string unique_filename = filename + ".sbp"; + while ((log_file_ = fopen(unique_filename.c_str(), "r"))) { + file_number++; + unique_filename = filename + "_" + std::to_string(file_number) + ".sbp"; + fclose(log_file_); + } + + log_file_ = fopen(unique_filename.c_str(), "wb"); // open binary file. return (log_file_ == nullptr); } void FileObservationLogger::close() { if (log_file_ != nullptr) { fclose(log_file_); + log_file_ = nullptr; } } +bool FileObservationLogger::isLogging() { return (log_file_ != nullptr); } + void FileObservationLogger::insertObservation( const piksi_multi_cpp::RawObservation& data) { - if (log_file_ != nullptr) { + file_mtx_.lock(); // write in chunks of 1byte for now. maybe blocked write might be a bit // faster. But because we don't write large amounts of data, it probably // doesn't matter too much fwrite(data.data(), sizeof(uint8_t), data.size(), log_file_); + file_mtx_.unlock(); } } FileObservationLogger::~FileObservationLogger() { close(); } -} \ No newline at end of file +} // namespace piksi_multi_cpp diff --git a/piksi_multi_cpp/src/receiver/receiver_base_station.cc b/piksi_multi_cpp/src/receiver/receiver_base_station.cc index 16e309b0..20196ab5 100644 --- a/piksi_multi_cpp/src/receiver/receiver_base_station.cc +++ b/piksi_multi_cpp/src/receiver/receiver_base_station.cc @@ -1,9 +1,9 @@ +#include "piksi_multi_cpp/receiver/receiver_base_station.h" #include #include #include #include #include -#include "piksi_multi_cpp/receiver/receiver_base_station.h" namespace piksi_multi_cpp { @@ -20,9 +20,6 @@ bool ReceiverBaseStation::init() { } // Setup UDP senders. - while (!readSetting("system_info", "sbp_sender_id")) { - } - sbp_sender_id_ = static_cast(std::stoul(getValue(), nullptr, 16)); ROS_INFO("UDP corrections sender ID: 0x%.4X", sbp_sender_id_); setupUDPSenders(); @@ -35,8 +32,8 @@ bool ReceiverBaseStation::init() { // The number of desired fixes is determined through the parameter // `num_desired_fixes` when autosampling or defined in the service call. void ReceiverBaseStation::setupBaseStationSampling() { - // Subscribe to maximum likelihood estimate and advertise service to overwrite - // current base station position. + // Subscribe to maximum likelihood estimate and advertise service to + // overwrite current base station position. resample_base_position_srv_ = nh_.advertiseService( "resample_base_position", &ReceiverBaseStation::resampleBasePositionCallback, this); diff --git a/piksi_multi_cpp/src/receiver/receiver_position.cc b/piksi_multi_cpp/src/receiver/receiver_position.cc index 87210eec..ebc35205 100644 --- a/piksi_multi_cpp/src/receiver/receiver_position.cc +++ b/piksi_multi_cpp/src/receiver/receiver_position.cc @@ -1,3 +1,7 @@ +#include +#include +#include + #include "piksi_multi_cpp/receiver/receiver_position.h" namespace piksi_multi_cpp { diff --git a/piksi_multi_cpp/src/receiver/receiver_ros.cc b/piksi_multi_cpp/src/receiver/receiver_ros.cc index 930763a3..3919a633 100644 --- a/piksi_multi_cpp/src/receiver/receiver_ros.cc +++ b/piksi_multi_cpp/src/receiver/receiver_ros.cc @@ -3,7 +3,6 @@ #include // SBP message definitions. -#include #include #include #include "piksi_multi_cpp/sbp_callback_handler/position_sampler.h" @@ -27,14 +26,106 @@ ReceiverRos::ReceiverRos(const ros::NodeHandle& nh, const Device::Ptr& device) // Create observation callbacks obs_cbs_ = std::make_unique(nh, state_); - if (1) { - auto logger = std::make_shared(); - /*ROS_WARN_STREAM(logger->open("/tmp/tempfile.sbp")); - obs_cbs_->addObservationCallbackListener( - CBtoRawObsConverter::createFor(logger));*/ + // Start file logger if requested + ros::NodeHandle nh_private("~"); + auto log_to_file = nh_private.param("log_observations_to_file", false); + start_stop_logger_srv_ = nh_.advertiseService( + "start_stop_obs_logger", &ReceiverRos::startStopFileLoggerCallback, this); + if (log_to_file) { + startFileLogger(); } } +bool ReceiverRos::init() { + if (!Receiver::init()) { + return false; + } + + // Get and store ID of device + while (!readSetting("system_info", "sbp_sender_id")) { + } + sbp_sender_id_ = static_cast(std::stoul(getValue(), nullptr, 16)); + + return true; +} + +void ReceiverRos::initObsLogger() { + obs_logger_ = std::make_shared(); + // Create ephemeris callbacks and add listeners to logger + eph_cbs_ = std::make_unique(nh_, state_); + // Add logger as listener to callbacks + obs_cbs_->addObservationCallbackListener( + CBtoRawObsConverter::createFor(obs_logger_, sbp_sender_id_)); + eph_cbs_->addObservationCallbackListener( + CBtoRawObsConverter::createFor(obs_logger_, sbp_sender_id_)); +} + +bool ReceiverRos::startFileLogger() { + ros::NodeHandle nh_private("~"); + auto obs_dir = nh_private.param("log_dir", "."); + std::string obs_filename; + std::size_t receiver_type_pos = nh_.getNamespace().find_last_of("/"); + std::string obs_prefix = + nh_.getNamespace().substr(receiver_type_pos + 1) + "_"; + + bool use_custom_filename = nh_private.hasParam("observation_filename"); + if (!use_custom_filename) { + std::time_t t = std::time(nullptr); + std::tm tm = *std::localtime(&t); + std::stringstream time_ss; + time_ss << std::put_time(&tm, "%Y_%d_%m_%H_%M_%S"); + obs_filename = obs_prefix + time_ss.str(); + } else { + // Get filename if custom name set + nh_private.getParam("observation_filename", obs_filename); + obs_filename = obs_prefix + obs_filename; + } + ROS_INFO_STREAM("Logging observations to file: \n\"" + << obs_dir << "/" << obs_filename << ".sbp\"."); + + // Initialize logger if not already done + if (!obs_logger_) { + initObsLogger(); + } + + // start logging + if (obs_logger_->open(obs_dir + "/" + obs_filename) != 0) { + ROS_WARN_STREAM( + "Could not open logger file. Observation are not being stored!"); + return false; + } + + return true; +} + +bool ReceiverRos::startStopFileLoggerCallback( + std_srvs::SetBool::Request& req, std_srvs::SetBool::Response& res) { + // Initialize logger if not already done + if (!obs_logger_) { + initObsLogger(); + } + + if (req.data && !obs_logger_->isLogging()) { + // Start logger if not running + if (startFileLogger()) { + res.success = true; + res.message = "Logger succesfully started"; + } else { + res.success = false; + res.message = "Failed to start logger."; + } + } else if (!req.data && obs_logger_->isLogging()) { + // Stop logger if runnning + obs_logger_->close(); + res.success = true; + res.message = "Stopped logging."; + } else { + res.success = false; + res.message = "Service call failed."; + } + return true; +} + std::vector ReceiverRos::getVectorParam( const std::string& name, const std::string& default_value) { auto string_value = nh_.param(name, default_value); diff --git a/piksi_multi_cpp/src/sbp_callback_handler/sbp_observation_callback_handler.cc b/piksi_multi_cpp/src/sbp_callback_handler/sbp_observation_callback_handler.cc deleted file mode 100644 index 824cc6db..00000000 --- a/piksi_multi_cpp/src/sbp_callback_handler/sbp_observation_callback_handler.cc +++ /dev/null @@ -1,23 +0,0 @@ -#include - -namespace piksi_multi_cpp { - -SBPObservationCallbackHandler::SBPObservationCallbackHandler( - const ros::NodeHandle nh, const std::shared_ptr& state) - : state_(state), - base_pos_handler_{getCallback(), - SBP_MSG_BASE_POS_ECEF, state}, - glo_bias_handler_{getCallback(), SBP_MSG_GLO_BIASES, - state}, - obs_handler_{getCallback(), SBP_MSG_OBS, state}, - heartbeat_handler_{getCallback(), SBP_MSG_HEARTBEAT, - state} {} - -void SBPObservationCallbackHandler::addObservationCallbackListener( - const CallbackObservationInterface::Ptr& listener) { - if (listener.get()) { - listeners_.push_back(listener); - } -} - -} // namespace piksi_multi_cpp diff --git a/piksi_multi_interface/package.xml b/piksi_multi_interface/package.xml index 68dcf04b..4eb6965e 100644 --- a/piksi_multi_interface/package.xml +++ b/piksi_multi_interface/package.xml @@ -13,6 +13,7 @@ roscpp std_msgs + std_srvs piksi_rtk_msgs libsbp_ros_msgs rosserial_arduino diff --git a/piksi_multi_interface/src/pushbutton_node.cc b/piksi_multi_interface/src/pushbutton_node.cc index 10ae9f7a..3f0f280d 100644 --- a/piksi_multi_interface/src/pushbutton_node.cc +++ b/piksi_multi_interface/src/pushbutton_node.cc @@ -3,6 +3,7 @@ #include #include #include +#include int main(int argc, char** argv) { ros::init(argc, argv, "piksi_pushbutton"); @@ -28,9 +29,16 @@ int main(int argc, char** argv) { ros::ServiceClient client = nh.serviceClient(service); + std::string obs_service = nh.getNamespace() + "/start_stop_obs_logger"; + ros::ServiceClient obs_client = + nh.serviceClient(obs_service); + int num_desired_fixes = is_base ? 1000 : 100; nh_private.getParam("num_desired_fixes", num_desired_fixes); + int raw_observation_sec = num_desired_fixes / 10; + ros::Duration raw_observations_dur(raw_observation_sec, 0); + double offset_z = is_base ? 0.0 : 2.0; nh_private.getParam("offset_z", offset_z); @@ -87,6 +95,14 @@ int main(int argc, char** argv) { srv.request.set_enu = is_base; srv.request.offset_z = offset_z; ROS_INFO_COND(client.call(srv), "Start sampling."); + + std_srvs::SetBool obs_srv; + obs_srv.request.data = true; + ROS_INFO_COND(obs_client.call(obs_srv), "Start recording observations."); + ros::Rate wait_for_obsv(raw_observations_dur); + wait_for_obsv.sleep(); + obs_srv.request.data = false; + ROS_INFO_COND(obs_client.call(obs_srv), "Stop recording observations."); } ros::spinOnce();