Skip to content

Commit

Permalink
updated rosplane to reflect new offboard command message definition
Browse files Browse the repository at this point in the history
  • Loading branch information
JMoore5353 committed Nov 26, 2024
1 parent 510e092 commit aa0f970
Show file tree
Hide file tree
Showing 2 changed files with 9 additions and 9 deletions.
8 changes: 4 additions & 4 deletions rosplane/src/controller_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -115,10 +115,10 @@ void ControllerBase::actuator_controls_publish()
actuators.mode = rosflight_msgs::msg::Command::MODE_PASS_THROUGH;

// Package control efforts. If the output is infinite replace with 0.
actuators.x = (std::isfinite(output.delta_a)) ? output.delta_a : 0.0f;
actuators.y = (std::isfinite(output.delta_e)) ? output.delta_e : 0.0f;
actuators.z = (std::isfinite(output.delta_r)) ? output.delta_r : 0.0f;
actuators.f = (std::isfinite(output.delta_t)) ? output.delta_t : 0.0f;
actuators.qx = (std::isfinite(output.delta_a)) ? output.delta_a : 0.0f;
actuators.qy = (std::isfinite(output.delta_e)) ? output.delta_e : 0.0f;
actuators.qz = (std::isfinite(output.delta_r)) ? output.delta_r : 0.0f;
actuators.fx = (std::isfinite(output.delta_t)) ? output.delta_t : 0.0f;

// Publish actuators.
actuators_pub_->publish(actuators);
Expand Down
10 changes: 5 additions & 5 deletions rosplane_extra/src/input_mapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -249,16 +249,16 @@ void InputMapper::command_callback(const rosflight_msgs::msg::Command::SharedPtr
{
u_int8_t ignore = rosflight_msgs::msg::Command::IGNORE_NONE;
if (params_.get_string("aileron_input") == "rc_aileron") {
ignore |= rosflight_msgs::msg::Command::IGNORE_X;
ignore |= rosflight_msgs::msg::Command::IGNORE_QX;
}
if (params_.get_string("elevator_input") == "rc_elevator") {
ignore |= rosflight_msgs::msg::Command::IGNORE_Y;
ignore |= rosflight_msgs::msg::Command::IGNORE_QY;
}
if (params_.get_string("rudder_input") == "rc_rudder") {
ignore |= rosflight_msgs::msg::Command::IGNORE_Z;
ignore |= rosflight_msgs::msg::Command::IGNORE_QZ;
}
if (params_.get_string("throttle_input") == "rc_throttle") {
ignore |= rosflight_msgs::msg::Command::IGNORE_F;
ignore |= rosflight_msgs::msg::Command::IGNORE_FX;
}
msg->ignore = ignore;
mapped_command_pub_->publish(*msg);
Expand Down Expand Up @@ -342,4 +342,4 @@ int main(int argc, char * argv[])
auto node = std::make_shared<rosplane::InputMapper>();
rclcpp::spin(node);
return 0;
}
}

0 comments on commit aa0f970

Please sign in to comment.