Class DemoSubPub
Defined in File demo_sub_pub.hpp
Inheritance Relationships
Base Type
public rclcpp::Node
Class Documentation
-
class DemoSubPub : public rclcpp::Node
A demonstration of a simple ROS2 node that raises numbers to a power and root
This node is used as a demo of how to setup a folder for a package, including various things like documentation and testing. The node itself listens to a custom message that contains a number and an exponent, then publishes a message with the number taken to the power and root of that exponent.
@rstb Topics Subscribed**:
num_power
(type :py:class:NumPwrData
): Publishes a message to topic/power_result
after message is received. @endrstTopics Published:
power_result
(type @rstNumPwrResult
@endrst ). A zero-valued message is published periodically. A message with appropriate values is published in response to a /num_power message.Public Functions
-
DemoSubPub()
-
inline virtual ~DemoSubPub()
called whenever a NumPwrData message is received.
- Parameters:
msg – [in] The message
-
void timer_callback()
called periodically to generate a default response
Public Members
-
rclcpp::Subscription<fqdemo_msgs::msg::NumPwrData>::SharedPtr subscriber_
subscription object for NumPwrData messages
-
rclcpp::TimerBase::SharedPtr timer_
periodic timter to generate some active output even if nothing incoming
-
rclcpp::Publisher<fqdemo_msgs::msg::NumPwrResult>::SharedPtr publisher_
publishes the results of apply_powers on the incoming message
-
size_t count_
counter used to display number of timer messages sent
Public Static Functions
-
static std::tuple<double, double> apply_powers(const double_t number, const double exponent)
Generate the root and power of a number.
- Parameters:
number – base value we want to take to a power or root
exponent – the exponent for the power or root
-
DemoSubPub()