remove unnecessary pipe operator from height
This commit is contained in:
@@ -13,18 +13,6 @@ using namespace std::chrono_literals;
|
|||||||
using terabee::DistanceData;
|
using terabee::DistanceData;
|
||||||
using terabee::ITerarangerEvoMini;
|
using terabee::ITerarangerEvoMini;
|
||||||
|
|
||||||
std::ostream &operator<<(std::ostream &os, const DistanceData &d)
|
|
||||||
{
|
|
||||||
os << "[";
|
|
||||||
for (size_t i = 0; i < d.distance.size(); i++)
|
|
||||||
{
|
|
||||||
os << d.distance[i] << ", ";
|
|
||||||
}
|
|
||||||
os << "\b\b"
|
|
||||||
<< " ]";
|
|
||||||
return os;
|
|
||||||
}
|
|
||||||
|
|
||||||
class HeightReader : public rclcpp::Node
|
class HeightReader : public rclcpp::Node
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
|
|||||||
@@ -9,7 +9,7 @@ using namespace std::chrono_literals;
|
|||||||
class HeartBeat : public rclcpp::Node
|
class HeartBeat : public rclcpp::Node
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
HeartBeat() : Node("setpoint_sender")
|
HeartBeat() : Node("heartbeat")
|
||||||
{
|
{
|
||||||
// create a publisher on the offboard control mode topic
|
// create a publisher on the offboard control mode topic
|
||||||
offboard_control_mode_publisher_ = this->create_publisher<px4_msgs::msg::OffboardControlMode>("/fmu/in/offboard_control_mode", 10);
|
offboard_control_mode_publisher_ = this->create_publisher<px4_msgs::msg::OffboardControlMode>("/fmu/in/offboard_control_mode", 10);
|
||||||
|
|||||||
Reference in New Issue
Block a user