Skip to content

Commit b4da8d7

Browse files
committed
Apply formating
1 parent 9365f7b commit b4da8d7

File tree

7 files changed

+282
-282
lines changed

7 files changed

+282
-282
lines changed

src/common.cpp

Lines changed: 19 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -8,7 +8,7 @@ namespace common
88

99
/* orientationError() //{ */
1010

11-
Eigen::Vector3d orientationError(const Eigen::Matrix3d& R, const Eigen::Matrix3d& Rd) {
11+
Eigen::Vector3d orientationError(const Eigen::Matrix3d &R, const Eigen::Matrix3d &Rd) {
1212

1313
// orientation error
1414
Eigen::Matrix3d R_error = 0.5 * (Rd.transpose() * R - R.transpose() * Rd);
@@ -28,8 +28,8 @@ Eigen::Vector3d orientationError(const Eigen::Matrix3d& R, const Eigen::Matrix3d
2828

2929
/* sanitizeDesiredForce() //{ */
3030

31-
std::optional<Eigen::Vector3d> sanitizeDesiredForce(const rclcpp::Node::SharedPtr& node, const Eigen::Vector3d& input, const double& tilt_safety_limit,
32-
const double& tilt_saturation, const std::string& node_name) {
31+
std::optional<Eigen::Vector3d> sanitizeDesiredForce(const rclcpp::Node::SharedPtr &node, const Eigen::Vector3d &input, const double &tilt_safety_limit,
32+
const double &tilt_saturation, const std::string &node_name) {
3333

3434
// calculate the force in spherical coordinates
3535
double theta = acos(input(2));
@@ -68,8 +68,8 @@ std::optional<Eigen::Vector3d> sanitizeDesiredForce(const rclcpp::Node::SharedPt
6868

6969
/* so3transform() //{ */
7070

71-
Eigen::Matrix3d so3transform(const rclcpp::Node::SharedPtr& node, const Eigen::Vector3d& body_z, const ::Eigen::Vector3d& heading,
72-
const bool& preserve_heading) {
71+
Eigen::Matrix3d so3transform(const rclcpp::Node::SharedPtr &node, const Eigen::Vector3d &body_z, const ::Eigen::Vector3d &heading,
72+
const bool &preserve_heading) {
7373

7474
Eigen::Vector3d body_z_normed = body_z.normalized();
7575

@@ -128,7 +128,7 @@ Eigen::Matrix3d so3transform(const rclcpp::Node::SharedPtr& node, const Eigen::V
128128

129129
/* getLowestOutput() //{ */
130130

131-
std::optional<CONTROL_OUTPUT> getLowestOuput(const mrs_uav_managers::control_manager::ControlOutputModalities_t& outputs) {
131+
std::optional<CONTROL_OUTPUT> getLowestOuput(const mrs_uav_managers::control_manager::ControlOutputModalities_t &outputs) {
132132

133133
if (outputs.actuators) {
134134
return ACTUATORS_CMD;
@@ -173,7 +173,7 @@ std::optional<CONTROL_OUTPUT> getLowestOuput(const mrs_uav_managers::control_man
173173

174174
/* getHighestOutput() //{ */
175175

176-
std::optional<CONTROL_OUTPUT> getHighestOuput(const mrs_uav_managers::control_manager::ControlOutputModalities_t& outputs) {
176+
std::optional<CONTROL_OUTPUT> getHighestOuput(const mrs_uav_managers::control_manager::ControlOutputModalities_t &outputs) {
177177

178178
if (outputs.position) {
179179
return POSITION;
@@ -218,7 +218,7 @@ std::optional<CONTROL_OUTPUT> getHighestOuput(const mrs_uav_managers::control_ma
218218

219219
/* extractThrottle() //{ */
220220

221-
std::optional<double> extractThrottle(const mrs_uav_managers::Controller::ControlOutput& control_output) {
221+
std::optional<double> extractThrottle(const mrs_uav_managers::Controller::ControlOutput &control_output) {
222222

223223
if (!control_output.control_output) {
224224
return {};
@@ -231,10 +231,10 @@ std::optional<double> extractThrottle(const mrs_uav_managers::Controller::Contro
231231

232232
/* attitudeController() //{ */
233233

234-
std::optional<mrs_msgs::msg::HwApiAttitudeRateCmd> attitudeController(const rclcpp::Node::SharedPtr& node, const mrs_msgs::msg::UavState& uav_state,
235-
const mrs_msgs::msg::HwApiAttitudeCmd& reference, const Eigen::Vector3d& ff_rate,
236-
const Eigen::Vector3d& rate_saturation, const Eigen::Vector3d& gains,
237-
const bool& parasitic_heading_rate_compensation) {
234+
std::optional<mrs_msgs::msg::HwApiAttitudeRateCmd> attitudeController(const rclcpp::Node::SharedPtr &node, const mrs_msgs::msg::UavState &uav_state,
235+
const mrs_msgs::msg::HwApiAttitudeCmd &reference, const Eigen::Vector3d &ff_rate,
236+
const Eigen::Vector3d &rate_saturation, const Eigen::Vector3d &gains,
237+
const bool &parasitic_heading_rate_compensation) {
238238

239239
Eigen::Matrix3d R = mrs_lib::AttitudeConverter(uav_state.pose.orientation);
240240
Eigen::Matrix3d Rd = mrs_lib::AttitudeConverter(reference.orientation);
@@ -254,7 +254,7 @@ std::optional<mrs_msgs::msg::HwApiAttitudeRateCmd> attitudeController(const rclc
254254
Eigen::Vector3d rp_heading_rate_compensation(0, 0, 0);
255255

256256
Eigen::Vector3d q_feedback_yawless = rate_feedback;
257-
q_feedback_yawless(2) = 0; // nullyfy the effect of the original yaw feedback
257+
q_feedback_yawless(2) = 0; // nullyfy the effect of the original yaw feedback
258258

259259
double parasitic_heading_rate = 0;
260260

@@ -314,8 +314,8 @@ std::optional<mrs_msgs::msg::HwApiAttitudeRateCmd> attitudeController(const rclc
314314

315315
/* attitudeRateController() //{ */
316316

317-
std::optional<mrs_msgs::msg::HwApiControlGroupCmd> attitudeRateController(const rclcpp::Node::SharedPtr& node, const mrs_msgs::msg::UavState& uav_state,
318-
const mrs_msgs::msg::HwApiAttitudeRateCmd& reference, const Eigen::Vector3d& gains) {
317+
std::optional<mrs_msgs::msg::HwApiControlGroupCmd> attitudeRateController(const rclcpp::Node::SharedPtr &node, const mrs_msgs::msg::UavState &uav_state,
318+
const mrs_msgs::msg::HwApiAttitudeRateCmd &reference, const Eigen::Vector3d &gains) {
319319

320320
Eigen::Vector3d des_rate(reference.body_rate.x, reference.body_rate.y, reference.body_rate.z);
321321
Eigen::Vector3d cur_rate(uav_state.velocity.angular.x, uav_state.velocity.angular.y, uav_state.velocity.angular.z);
@@ -339,8 +339,8 @@ std::optional<mrs_msgs::msg::HwApiControlGroupCmd> attitudeRateController(const
339339

340340
/* actuatorMixer() //{ */
341341

342-
mrs_msgs::msg::HwApiActuatorCmd actuatorMixer(const rclcpp::Node::SharedPtr& node, const mrs_msgs::msg::HwApiControlGroupCmd& ctrl_group_cmd,
343-
const Eigen::MatrixXd& mixer) {
342+
mrs_msgs::msg::HwApiActuatorCmd actuatorMixer(const rclcpp::Node::SharedPtr &node, const mrs_msgs::msg::HwApiControlGroupCmd &ctrl_group_cmd,
343+
const Eigen::MatrixXd &mixer) {
344344

345345
Eigen::Vector4d ctrl_group(ctrl_group_cmd.roll, ctrl_group_cmd.pitch, ctrl_group_cmd.yaw, ctrl_group_cmd.throttle);
346346

@@ -385,6 +385,6 @@ mrs_msgs::msg::HwApiActuatorCmd actuatorMixer(const rclcpp::Node::SharedPtr& nod
385385

386386
//}
387387

388-
} // namespace common
388+
} // namespace common
389389

390-
} // namespace mrs_uav_controllers
390+
} // namespace mrs_uav_controllers

src/failsafe_controller.cpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -55,8 +55,8 @@ class FailsafeController : public mrs_uav_managers::Controller {
5555

5656
void resetDisturbanceEstimators(void);
5757

58-
const std::shared_ptr<mrs_msgs::srv::DynamicsConstraintsSrv::Response> setConstraints(
59-
const std::shared_ptr<mrs_msgs::srv::DynamicsConstraintsSrv::Request> &constraints);
58+
const std::shared_ptr<mrs_msgs::srv::DynamicsConstraintsSrv::Response>
59+
setConstraints(const std::shared_ptr<mrs_msgs::srv::DynamicsConstraintsSrv::Request> &constraints);
6060

6161
double getHeadingSafely(const geometry_msgs::msg::QuaternionStamped::ConstSharedPtr quaternion);
6262

@@ -530,8 +530,8 @@ void FailsafeController::resetDisturbanceEstimators(void) {
530530

531531
/* setConstraints() //{ */
532532

533-
const std::shared_ptr<mrs_msgs::srv::DynamicsConstraintsSrv::Response> FailsafeController::setConstraints(
534-
[[maybe_unused]] const std::shared_ptr<mrs_msgs::srv::DynamicsConstraintsSrv::Request> &constraints) {
533+
const std::shared_ptr<mrs_msgs::srv::DynamicsConstraintsSrv::Response>
534+
FailsafeController::setConstraints([[maybe_unused]] const std::shared_ptr<mrs_msgs::srv::DynamicsConstraintsSrv::Request> &constraints) {
535535

536536
std::shared_ptr<mrs_msgs::srv::DynamicsConstraintsSrv::Response> response = std::make_shared<mrs_msgs::srv::DynamicsConstraintsSrv::Response>();
537537

@@ -576,9 +576,9 @@ double FailsafeController::getHeadingSafely(const geometry_msgs::msg::Quaternion
576576

577577
//}
578578

579-
} // namespace failsafe_controller
579+
} // namespace failsafe_controller
580580

581-
} // namespace mrs_uav_controllers
581+
} // namespace mrs_uav_controllers
582582

583583
#include <pluginlib/class_list_macros.hpp>
584584
PLUGINLIB_EXPORT_CLASS(mrs_uav_controllers::failsafe_controller::FailsafeController, mrs_uav_managers::Controller)

0 commit comments

Comments
 (0)