#include <labust/preprocessor/mem_serialized_struct.hpp>
#include <labust/tools/StringUtilities.hpp>
#include <cart2/RadioModemConfig.h>
#include <std_msgs/Float32MultiArray.h>
#include <labust/control/crc16.h>
#include <dynamic_reconfigure/server.h>
#include <boost/asio.hpp>
#include <boost/thread/mutex.hpp>
#include <boost/thread.hpp>
#include <boost/archive/binary_oarchive.hpp>
#include <sensor_msgs/Joy.h>
#include <std_msgs/Int32.h>
#include <geometry_msgs/PointStamped.h>
#include <tf/transform_listener.h>
#include <tf/transform_broadcaster.h>
#include <auv_msgs/NavSts.h>
#include <ros/ros.h>
#include <sstream>
Go to the source code of this file.
Functions | |
PP_LABUST_DEFINE_BOOST_SERIALIZED_STRUCT_CLEAN ((labust)(radio), TopsideModemData,(int8_t, surgeForce)(int8_t, torqueForce)(int32_t, lat)(int32_t, lon)(uint8_t, radius)(uint8_t, surge)(int8_t, yaw)(uint8_t, mode)(uint8_t, launch)(uint8_t, mode_update)) namespace labust | |
PP_LABUST_DEFINE_BOOST_SERIALIZED_STRUCT_CLEAN ((labust)(radio), CARTModemData,(int32_t, origin_lat)(int32_t, origin_lon)(uint8_t, mode)(measVec, state_meas)(stateVec, state_hat)(measVec, sf_state)(int16_t, portRPM)(int16_t, stbdRPM)(uint8_t, voltage)(uint8_t, temp)) namespace labust |
PP_LABUST_DEFINE_BOOST_SERIALIZED_STRUCT_CLEAN | ( | (labust)(radio) | , |
TopsideModemData | , | ||
(int8_t, surgeForce)(int8_t, torqueForce)(int32_t, lat)(int32_t, lon)(uint8_t, radius)(uint8_t, surge)(int8_t, yaw)(uint8_t, mode)(uint8_t, launch)(uint8_t, mode_update) | |||
) |
The topside transmitted message.
force, torque - (-100,100)
Definition at line 66 of file TopsideRadio.hpp.
PP_LABUST_DEFINE_BOOST_SERIALIZED_STRUCT_CLEAN | ( | (labust)(radio) | , |
CARTModemData | , | ||
(int32_t, origin_lat)(int32_t, origin_lon)(uint8_t, mode)(measVec, state_meas)(stateVec, state_hat)(measVec, sf_state)(int16_t, portRPM)(int16_t, stbdRPM)(uint8_t, voltage)(uint8_t, temp) | |||
) |
The class implements the topside radio modem node.
Main constructor
Main deconstructor
Initialize and setup the manager.
Start the radio node.
Dynamic reconfigure callback.
Handle the joystick input.
Handle the external target point.
Handle the estimates.
Handle the measurements.
Handle the measurements.
Helper function.
Helper function.
Helper function.
Start the receiving thread.
Handle incoming modem data.
Handle incoming modem data.
Helper function for checksum calculation.
Helper function for checksum calculation.
Modem timeout detection.
The ROS node handles.
The last arrived message.
The timeout length.
The publishers.
The subscribed topics.
The transform listener.
The transform broadcaster.
The io service.
The serial port
The io service thread.
The dynamic reconfigure server.
The last dynamic reconfiguration.
Exchanged data.
The return data.
The data protector.
The asio streambuffer.
The sync buffer.
Location flag.
The service client.
The frame transformer.
Definition at line 89 of file TopsideRadio.hpp.