Skip to content

SmartArmStack/sas_datalogger

 
 

Repository files navigation

sas_datalogger

Log data through ROS2 into a .mat-compliant file.

Main goodies

Node

Call with ros2 run sas_datalogger <NODE_NAME>.

Node name Description
sas_datalogger_node.py The main node that will store the data received through specialised topics.
#include <sas_datalogger/sas_datalogger_client.hpp> The DataloggerClient that must be used for cpp binaries.
from sas_datalogger import DataloggerClient The DataloggerClient that must be used in Python scripts.

Example

cd docker
docker compose up

CPP Usage

Refer to the example src/examples/sas_datalogger_client_example.cpp.

#include <rclcpp/rclcpp.hpp>
#include <sas_common/sas_common.hpp>
#include <sas_datalogger/sas_datalogger_client.hpp>
/*********************************************
* SIGNAL HANDLER
* *******************************************/
#include<signal.h>
static std::atomic_bool kill_this_process(false);
void sig_int_handler(int)
{
kill_this_process = true;
}
int main(int argc,char** argv)
{
if(signal(SIGINT, sig_int_handler) == SIG_ERR)
{
throw std::runtime_error("::Error setting the signal int handler.");
}
rclcpp::init(argc,argv,rclcpp::InitOptions(),rclcpp::SignalHandlerOptions::None);
auto node = std::make_shared<rclcpp::Node>("sas_datalogger_client_example");
try
{
sas::DataloggerClient datalogger_client(node); //If you're storing more than 100 values at each loop, this might need adjustment
RCLCPP_WARN_STREAM_ONCE(node->get_logger(), "*******RUN THIS EXAMPLE WITH THE LAUNCH FILE, NOT THE BINARY DIRECTLY.*******");
RCLCPP_WARN_STREAM_ONCE(node->get_logger(), "Run with 'ros2 launch sas_datalogger sas_datalogger_client_example_launch.py'");
RCLCPP_WARN_STREAM_ONCE(node->get_logger(), "*****************************************************************************");
RCLCPP_INFO_STREAM_ONCE(node->get_logger(), "Waiting for a connection with sas_datalogger...");
while( (not datalogger_client.is_enabled()) and (not kill_this_process))
{
std::this_thread::sleep_for(std::chrono::microseconds(100));
rclcpp::spin_some(node);
}
RCLCPP_INFO_STREAM_ONCE(node->get_logger(), "Connected to sas_datalogger.");
RCLCPP_INFO_STREAM_ONCE(node->get_logger(), "Logging started...");
RCLCPP_INFO_STREAM_ONCE(node->get_logger(), "Logging each value 5 times...");
for (auto i = 0; i < 5; i++)
{
MatrixXd A(3,4); A << 1,2,3,4,5,6,7,8,9,10,11,12;
datalogger_client.log("A",A);
VectorXd v(5); v << 1,5,10,15,20;
datalogger_client.log("v",v);
std::vector<double> std_v = {2,4,6,8,10};
datalogger_client.log("std_v",std_v);
datalogger_client.log("value_double",5);
datalogger_client.log("value_string","Hello world!");
}
RCLCPP_INFO_STREAM_ONCE(node->get_logger(), "Logging ended. Close the `sas_datalogger_node` and check the resulting .mat file.");
while(not kill_this_process)
{
std::this_thread::sleep_for(std::chrono::microseconds(100));
rclcpp::spin_some(node);
}
}
catch (const std::exception& e)
{
RCLCPP_ERROR_STREAM_ONCE(node->get_logger(), std::string("::Exception::") + e.what());
}
sas::display_signal_handler_none_bug_info(node);
return 0;
}

Python Usage

Refer to the example scripts/sas_datalogger_client_example_py.py.

import numpy as np
from sas_datalogger import DataloggerClient
from sas_core import Clock
from sas_common import rclcpp_init, rclcpp_Node, rclcpp_spin_some, rclcpp_shutdown
def main(args=None):
"""
An example showing some of the functionalites of the DataloggerClient.
:param args: Not used directly by the user, but used by ROS2 to configure
certain aspects of the Node.
"""
try:
rclcpp_init() # Init rclcpp to use the sas python bindings. They do not use rclpy.
# However, you can also have rclpy nodes active as long as you manage their spin
# correctly.
rclcpp_node = rclcpp_Node("sas_datalogger_client_example_py")
datalogger_client = DataloggerClient(rclcpp_node)
clock = Clock(0.001)
clock.init()
while not datalogger_client.is_enabled():
rclcpp_spin_some(rclcpp_node)
clock.update_and_sleep()
for i in range(0, 5):
A = np.array([[1, 2, 3],
[4, 5, 6],
[7, 8, 9],
[10, 11, 12]])
datalogger_client.log("A", A)
v = np.array([1, 5, 10, 15, 20])
datalogger_client.log("v", v)
datalogger_client.log("value_double", 5)
datalogger_client.log("value_string", "Hello world!")
clock.init()
while True:
rclcpp_spin_some(rclcpp_node)
clock.update_and_sleep()
rclcpp_shutdown() # Shutdown rclcpp
except KeyboardInterrupt:
print("Interrupted by user")
if __name__ == '__main__':
main()

About

No description, website, or topics provided.

Resources

Stars

Watchers

Forks

Releases

No releases published

Packages

 
 
 

Contributors

Languages

  • C++ 45.7%
  • Python 36.2%
  • CMake 15.4%
  • Shell 1.5%
  • Dockerfile 1.2%