#include <xsens_common_node.hpp>
|
| XsensCommonNode (const std::string &node_name, const std::string &device_name, const typename autoware::drivers::serial_driver::SerialDriverNode< XsensCommonNode< TranslatorT, MessageT >, typename TranslatorT::Packet, MessageT > ::SerialPortConfig &serial_port_config, const std::string &frame_id, const typename TranslatorT::Config &config) |
| Default constructor, starts driver. More...
|
|
| XsensCommonNode (const std::string &node_name, const std::string &node_namespace="") |
| Parameter file constructor. More...
|
|
void | init_output (MessageT &output) |
|
bool8_t | convert (const typename TranslatorT::Packet &pkt, MessageT &output) |
|
bool8_t | get_output_remainder (MessageT &output) |
|
◆ XsensCommonNode() [1/2]
template<typename TranslatorT , typename MessageT >
autoware::drivers::xsens_nodes::XsensCommonNode< TranslatorT, MessageT >::XsensCommonNode |
( |
const std::string & |
node_name, |
|
|
const std::string & |
device_name, |
|
|
const typename autoware::drivers::serial_driver::SerialDriverNode< XsensCommonNode< TranslatorT, MessageT >, typename TranslatorT::Packet, MessageT > ::SerialPortConfig & |
serial_port_config, |
|
|
const std::string & |
frame_id, |
|
|
const typename TranslatorT::Config & |
config |
|
) |
| |
|
inline |
Default constructor, starts driver.
- Parameters
-
[in] | node_name | name of the node for rclcpp internals |
[in] | device_name | Name of the serial device. |
[in] | serial_port_config | config struct with baud_rate, flow_control, parity and stop_bits params |
[in] | frame_id | Frame id for the published point cloud messages |
[in] | config | Config struct with rpm, transform, radial and angle pruning params |
- Exceptions
-
std::runtime_error | If cloud_size is not sufficiently large |
◆ XsensCommonNode() [2/2]
template<typename TranslatorT , typename MessageT >
Parameter file constructor.
- Parameters
-
[in] | node_name | Name of this node |
[in] | node_namespace | Namespace for this node |
◆ convert()
template<typename TranslatorT , typename MessageT >
◆ get_output_remainder()
template<typename TranslatorT , typename MessageT >
◆ init_output()
template<typename TranslatorT , typename MessageT >
The documentation for this class was generated from the following file: