Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

trajectory setpoint: finish update method #27

Merged
merged 1 commit into from
Feb 16, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
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
Loading