Skip to content

Commit

Permalink
trajectory setpoint: complete update method
Browse files Browse the repository at this point in the history
  • Loading branch information
GuillaumeLaine committed Feb 13, 2024
1 parent b481656 commit 30328a1
Show file tree
Hide file tree
Showing 3 changed files with 29 additions and 11 deletions.
1 change: 0 additions & 1 deletion examples/cpp/modes/rtl_replacement/include/mode.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,6 @@ class FlightModeTest : public px4_ros2::ModeBase
completed(px4_ros2::Result::Success);
return;
}

const Eigen::Vector3f velocity{0.f, 1.f, 5.f};
_trajectory_setpoint->update(velocity);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,11 @@ class TrajectorySetpointType : public SetpointBase

Configuration getConfiguration() override;

void update(const Eigen::Vector3f & velocity_setpoint_ned_m_s);
void update(
const Eigen::Vector3f & velocity_ned_m_s,
const std::optional<Eigen::Vector3f> & acceleration_ned_m_s2 = {},
std::optional<float> yaw_ned_rad = {},
std::optional<float> yaw_rate_ned_rad_s = {});

private:
rclcpp::Node & _node;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,27 +16,42 @@ TrajectorySetpointType::TrajectorySetpointType(Context & context)
context.topicNamespacePrefix() + "/fmu/in/trajectory_setpoint", 1);
}

void TrajectorySetpointType::update(const Eigen::Vector3f & velocity_setpoint_ned_m_s)
void TrajectorySetpointType::update(
const Eigen::Vector3f & velocity_ned_m_s,
const std::optional<Eigen::Vector3f> & acceleration_ned_m_s2,
std::optional<float> yaw_ned_rad,
std::optional<float> yaw_rate_ned_rad_s)
{
onUpdate();

px4_msgs::msg::TrajectorySetpoint sp{};
// TODO
sp.yaw = NAN;
sp.yawspeed = NAN;
sp.position[0] = sp.position[1] = sp.position[2] = NAN;
sp.acceleration[0] = sp.acceleration[1] = sp.acceleration[2] = NAN;
sp.velocity[0] = velocity_setpoint_ned_m_s(0);
sp.velocity[1] = velocity_setpoint_ned_m_s(1);
sp.velocity[2] = velocity_setpoint_ned_m_s(2);
sp.timestamp = _node.get_clock()->now().nanoseconds() / 1000;

sp.position[0] = sp.position[1] = sp.position[2] = NAN;
sp.velocity[0] = velocity_ned_m_s.x();
sp.velocity[1] = velocity_ned_m_s.y();
sp.velocity[2] = velocity_ned_m_s.z();
Eigen::Vector3f acceleration = acceleration_ned_m_s2.value_or(Eigen::Vector3f{NAN, NAN, NAN});
sp.acceleration[0] = acceleration.x();
sp.acceleration[1] = acceleration.y();
sp.acceleration[2] = acceleration.z();
sp.yaw = yaw_ned_rad.value_or(NAN);
sp.yawspeed = yaw_rate_ned_rad_s.value_or(NAN);

_trajectory_setpoint_pub->publish(sp);

}

SetpointBase::Configuration TrajectorySetpointType::getConfiguration()
{
Configuration config{};
config.rates_enabled = true;
config.attitude_enabled = true;
config.acceleration_enabled = true;
config.velocity_enabled = true;
config.position_enabled = true;
config.altitude_enabled = true;
config.climb_rate_enabled = true;
return config;
}
} // namespace px4_ros2

0 comments on commit 30328a1

Please sign in to comment.