23 float centerX,
float centerY,
float altitude,
float radius,
float angularVelocity,
int numOrbits)
28 angularVelocity_(angularVelocity),
52 getLogger(),
"CbOrbitLocation: starting orbit center=[%.2f, %.2f] r=%.2f alt=%.2f orbits=%d",
62 auto now = std::chrono::steady_clock::now();
63 double dt = std::chrono::duration<double>(now -
lastUpdateTime_).count();
79 float requiredAngle =
numOrbits_ * 2.0f * M_PI;
81 if (totalAngle >= requiredAngle)
83 RCLCPP_INFO(
getLogger(),
"CbOrbitLocation: %d orbits completed - posting success",
numOrbits_);
std::chrono::steady_clock::time_point lastUpdateTime_
CpVehicleLocalPosition * localPosition_
CbOrbitLocation(float centerX, float centerY, float altitude, float radius=5.0f, float angularVelocity=0.5f, int numOrbits=3)
CpTrajectorySetpoint * trajectorySetpoint_
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)