23 float centerX,
float centerY,
float altitude,
float maxRadius,
float spacing,
float speed)
27 maxRadius_(maxRadius),
46 "CbSpiralPattern: starting spiral center=[%.2f, %.2f] alt=%.2f maxR=%.2f spacing=%.2f "
57 auto now = std::chrono::steady_clock::now();
58 double dt = std::chrono::duration<double>(now -
lastUpdateTime_).count();
71 float omega =
speed_ / std::sqrt(r * r + a * a);
85 float dxdt = a * std::cos(
theta_) - r_new * std::sin(
theta_);
86 float dydt = a * std::sin(
theta_) + r_new * std::cos(
theta_);
87 float yaw = std::atan2(dydt, dxdt);
95 getLogger(),
"CbSpiralPattern: max radius %.2f reached (r=%.2f) - posting success",
CpVehicleLocalPosition * localPosition_
CpTrajectorySetpoint * trajectorySetpoint_
std::chrono::steady_clock::time_point lastUpdateTime_
CbSpiralPattern(float centerX, float centerY, float altitude, float maxRadius=20.0f, float spacing=3.0f, float speed=2.0f)
void setPositionNED(float x, float y, float z, float yaw=std::numeric_limits< float >::quiet_NaN())
virtual rclcpp::Logger getLogger() const
void requiresComponent(SmaccComponentType *&storage, ComponentRequirement requirementType=ComponentRequirement::SOFT)