Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add UBX-MON-SYS message to Firmware Gen. 9 #250

Open
wants to merge 1 commit into
base: ros2
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -165,6 +165,7 @@ To publish a given u-blox message to a ROS topic, set the parameter shown below
### MON messages
* `publish/mon/all`: This is the default value for the `publish/mon/<message>` parameters below. It defaults to `publish/all`. Individual messages can be enabled or disabled by setting the parameters below.
* `publish/mon/hw`: Topic `~monhw`
* `publish/mon/sys`: Topic `~monsys`

### NAV messages
* `publish/nav/all`: This is the default value for the `publish/mon/<message>` parameters below. It defaults to `publish/all`. Individual messages can be enabled or disabled by setting the parameters below.
Expand Down
7 changes: 7 additions & 0 deletions ublox_gps/include/ublox_gps/ublox_firmware9.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@

#include <ublox_msgs/msg/cfg_valset.hpp>
#include <ublox_msgs/msg/cfg_valset_cfgdata.hpp>
#include <ublox_msgs/msg/mon_sys.hpp>

#include <ublox_gps/fix_diagnostic.hpp>
#include <ublox_gps/gnss.hpp>
Expand All @@ -34,13 +35,19 @@ class UbloxFirmware9 final : public UbloxFirmware8 {
*/
bool configureUblox(std::shared_ptr<ublox_gps::Gps> gps) override;

/**
* @brief Subscribe to MonSYS messages.
*/
void subscribe(std::shared_ptr<ublox_gps::Gps> gps) override;

private:
/**
* @brief Populate the CfgVALSETCfgData data type
*
* @details A helper function used to generate a configuration for a single signal.
*/
ublox_msgs::msg::CfgVALSETCfgdata generateSignalConfig(uint32_t signalID, bool enable);
rclcpp::Publisher<ublox_msgs::msg::MonSYS>::SharedPtr mon_sys_pub_;
};

} // namespace ublox_node
Expand Down
1 change: 1 addition & 0 deletions ublox_gps/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -440,6 +440,7 @@ void UbloxNode::getRosParams() {

this->declare_parameter("publish.mon.all", getRosBoolean(this, "publish.all"));
this->declare_parameter("publish.mon.hw", getRosBoolean(this, "publish.mon.all"));
this->declare_parameter("publish.mon.sys", getRosBoolean(this, "publish.mon.all"));

this->declare_parameter("publish.tim.tm2", false);

Expand Down
15 changes: 15 additions & 0 deletions ublox_gps/src/ublox_firmware9.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,11 @@ namespace ublox_node {
UbloxFirmware9::UbloxFirmware9(const std::string & frame_id, std::shared_ptr<diagnostic_updater::Updater> updater, std::shared_ptr<FixDiagnostic> freq_diag, std::shared_ptr<Gnss> gnss, rclcpp::Node* node)
: UbloxFirmware8(frame_id, updater, freq_diag, gnss, node)
{
if (getRosBoolean(node_, "publish.mon.sys"))
{
mon_sys_pub_ =
node_->create_publisher<ublox_msgs::msg::MonSYS>("monsys", 1);
}
}

bool UbloxFirmware9::configureUblox(std::shared_ptr<ublox_gps::Gps> gps)
Expand Down Expand Up @@ -118,5 +123,15 @@ ublox_msgs::msg::CfgVALSETCfgdata UbloxFirmware9::generateSignalConfig(uint32_t
return signalConfig;
}

void UbloxFirmware9::subscribe(std::shared_ptr<ublox_gps::Gps> gps)
{
UbloxFirmware8::subscribe(gps);

// Subscribe to Mon SYS messages
if (getRosBoolean(node_, "publish.mon.sys")) {
gps->subscribe<ublox_msgs::msg::MonSYS>([this](const ublox_msgs::msg::MonSYS &m) {
mon_sys_pub_->publish(m); }, 1);
}
}

} // namespace ublox_node
1 change: 1 addition & 0 deletions ublox_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,7 @@ set(msg_files
"msg/MonGNSS.msg"
"msg/MonHW6.msg"
"msg/MonHW.msg"
"msg/MonSYS.msg"
"msg/MonVERExtension.msg"
"msg/MonVER.msg"
"msg/NavATT.msg"
Expand Down
54 changes: 54 additions & 0 deletions ublox_msgs/include/ublox_msgs/serialization.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -1500,6 +1500,60 @@ struct UbloxSerializer<ublox_msgs::msg::MonHW6_<ContainerAllocator> > {
}
};

template <typename ContainerAllocator>
struct UbloxSerializer<ublox_msgs::msg::MonSYS_<ContainerAllocator> > {
inline static void read(const uint8_t *data, uint32_t count,
ublox_msgs::msg::MonSYS_<ContainerAllocator> & m) {
UbloxIStream stream(const_cast<uint8_t *>(data), count);
stream.next(m.version);
stream.next(m.boot_type);
stream.next(m.cpu_load);
stream.next(m.cpu_load_max);
stream.next(m.mem_usage);
stream.next(m.mem_usage_max);
stream.next(m.io_usage);
stream.next(m.io_usage_max);
stream.next(m.run_time);
stream.next(m.notice_count);
stream.next(m.warning_count);
stream.next(m.error_count);
stream.next(m.temperature);
stream.next(m.reserved0[0]);
stream.next(m.reserved0[1]);
stream.next(m.reserved0[2]);
stream.next(m.reserved0[3]);
stream.next(m.reserved0[4]);
}

inline static uint32_t serializedLength(const ublox_msgs::msg::MonSYS_<ContainerAllocator> & m) {
(void)m;
return 24;
}

inline static void write(uint8_t *data, uint32_t size,
const ublox_msgs::msg::MonSYS_<ContainerAllocator> & m) {
UbloxOStream stream(data, size);
stream.next(m.version);
stream.next(m.boot_type);
stream.next(m.cpu_load);
stream.next(m.cpu_load_max);
stream.next(m.mem_usage);
stream.next(m.mem_usage_max);
stream.next(m.io_usage);
stream.next(m.io_usage_max);
stream.next(m.run_time);
stream.next(m.notice_count);
stream.next(m.warning_count);
stream.next(m.error_count);
stream.next(m.temperature);
stream.next(m.reserved0[0]);
stream.next(m.reserved0[1]);
stream.next(m.reserved0[2]);
stream.next(m.reserved0[3]);
stream.next(m.reserved0[4]);
}
};

template <typename ContainerAllocator>
struct UbloxSerializer<ublox_msgs::msg::MonVERExtension_<ContainerAllocator> > {
inline static void read(UbloxIStream& stream, ublox_msgs::msg::MonVERExtension_<ContainerAllocator> & m) {
Expand Down
2 changes: 2 additions & 0 deletions ublox_msgs/include/ublox_msgs/ublox_msgs.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -96,6 +96,7 @@
#include <ublox_msgs/msg/mon_gnss.hpp>
#include <ublox_msgs/msg/mon_hw.hpp>
#include <ublox_msgs/msg/mon_hw6.hpp>
#include <ublox_msgs/msg/mon_sys.hpp>
#include <ublox_msgs/msg/mon_ver.hpp>

#include <ublox_msgs/msg/aid_alm.hpp>
Expand Down Expand Up @@ -240,6 +241,7 @@ namespace Message {
namespace MON {
static const uint8_t GNSS = ublox_msgs::msg::MonGNSS::MESSAGE_ID;
static const uint8_t HW = ublox_msgs::msg::MonHW::MESSAGE_ID;
static const uint8_t SYS = ublox_msgs::msg::MonSYS::MESSAGE_ID;
static const uint8_t VER = ublox_msgs::msg::MonVER::MESSAGE_ID;
} // namespace MON

Expand Down
37 changes: 37 additions & 0 deletions ublox_msgs/msg/MonSYS.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
# MON-SYS (0x0A 0x39)
# System Performance Information
#
# This message contains operationally relevant system information for
# monitoring purposes.


uint8 CLASS_ID = 10 # 0x0A
uint8 MESSAGE_ID = 57 # 0x39

uint8 version # Message Version (0x01 for this version)
uint8 boot_type # Boot type of master chip
uint8 BOOT_TYPE_UNKOWN = 0
uint8 BOOT_TYPE_COLD_START = 1
uint8 BOOT_TYPE_WATCHDOG = 2
uint8 BOOT_TYPE_HW_RESET = 3
uint8 BOOT_TYPE_HW_BACKUP = 4
uint8 BOOT_TYPE_SW_BACKUP = 5
uint8 BOOT_TYPE_SW_RESET = 6
uint8 BOOT_TYPE_VIO_FAIL = 7
uint8 BOOT_TYPE_VDD_X_FAIL = 8
uint8 BOOT_TYPE_VDD_RF_FAIL = 9
uint8 BOOT_TYPE_V_CORE_HIGH_FAIL = 10

uint8 cpu_load # CPU Load [%]
uint8 cpu_load_max # Maximum CPU Load [%] since last restart
uint8 mem_usage # Memory Usage [%]
uint8 mem_usage_max # Maximum Memory Usage [%] since last restart
uint8 io_usage # I/O Usage [%]
uint8 io_usage_max # Maximum I/O Usage [%] since last restart
uint32 run_time # Uptime [s] since last restart
uint16 notice_count # Number of notices since last restart
uint16 warning_count # Number of warnings since last restart
uint16 error_count # Number of errors since last restart
int16 temperature # Temperature [°C]

uint8[5] reserved0 # Reserved for future use
2 changes: 2 additions & 0 deletions ublox_msgs/src/ublox_msgs.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -179,6 +179,8 @@ DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::MON, ublox_msgs::Message::MON::HW,
ublox_msgs, MonHW)
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::MON, ublox_msgs::Message::MON::HW,
ublox_msgs, MonHW6)
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::MON, ublox_msgs::Message::MON::SYS,
ublox_msgs, MonSYS)
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::MON, ublox_msgs::Message::MON::VER,
ublox_msgs, MonVER)

Expand Down