diff --git a/include/mrs_multirotor_simulator/uav_system/multirotor_model.hpp b/include/mrs_multirotor_simulator/uav_system/multirotor_model.hpp index 9ca181b..930ab25 100644 --- a/include/mrs_multirotor_simulator/uav_system/multirotor_model.hpp +++ b/include/mrs_multirotor_simulator/uav_system/multirotor_model.hpp @@ -373,10 +373,6 @@ void MultirotorModel::operator()(const MultirotorModel::InternalState& x, Multir void MultirotorModel::setParams(const MultirotorModel::ModelParams& params) { params_ = params; - - initializeState(); - - updateInternalState(); } //} diff --git a/include/mrs_multirotor_simulator/uav_system/uav_system.hpp b/include/mrs_multirotor_simulator/uav_system/uav_system.hpp index 1457b75..71c1fb6 100644 --- a/include/mrs_multirotor_simulator/uav_system/uav_system.hpp +++ b/include/mrs_multirotor_simulator/uav_system/uav_system.hpp @@ -62,6 +62,8 @@ class UavSystem { MultirotorModel::State getState(void); MultirotorModel::ModelParams getParams(void); + void setParams(const MultirotorModel::ModelParams& params); + Eigen::Vector3d getImuAcceleration(void); void setMixerParams(const Mixer::Params& params); @@ -392,6 +394,17 @@ MultirotorModel::ModelParams UavSystem::getParams(void) { //} +/* setParams() //{ */ + +void UavSystem::setParams(const MultirotorModel::ModelParams& params) { + + multirotor_model_.setParams(params); + + initializeControllers(); +} + +//} + /* getMixerAllocation() //{ */ Eigen::MatrixXd UavSystem::getMixerAllocation(void) { diff --git a/include/mrs_multirotor_simulator/uav_system_ros.h b/include/mrs_multirotor_simulator/uav_system_ros.h index d3a77fd..bb06b3e 100644 --- a/include/mrs_multirotor_simulator/uav_system_ros.h +++ b/include/mrs_multirotor_simulator/uav_system_ros.h @@ -17,6 +17,7 @@ #include #include #include +#include #include #include @@ -121,6 +122,20 @@ class UavSystemRos { mrs_lib::SubscribeHandler sh_velocity_hdg_cmd_; mrs_lib::SubscribeHandler sh_position_cmd_; mrs_lib::SubscribeHandler sh_tracker_cmd_; + + // | --------------------- service servers -------------------- | + + ros::ServiceServer service_server_set_mass_; + + ros::ServiceServer service_server_set_ground_z_; + + bool callbackSetMass(mrs_msgs::Float64Srv::Request& req, mrs_msgs::Float64Srv::Response& res); + + bool callbackSetGroundZ(mrs_msgs::Float64Srv::Request& req, mrs_msgs::Float64Srv::Response& res); + + // | ------------------------ routines ------------------------ | + + void calculateInertia(MultirotorModel::ModelParams& params); }; } // namespace mrs_multirotor_simulator diff --git a/launch/multirotor_simulator.launch b/launch/multirotor_simulator.launch index 6798f66..9bbdcae 100644 --- a/launch/multirotor_simulator.launch +++ b/launch/multirotor_simulator.launch @@ -50,17 +50,6 @@ - - - - - - - - - - - diff --git a/src/uav_system_ros.cpp b/src/uav_system_ros.cpp index b57a9f8..47ec4fd 100644 --- a/src/uav_system_ros.cpp +++ b/src/uav_system_ros.cpp @@ -93,13 +93,7 @@ UavSystemRos::UavSystemRos(ros::NodeHandle &nh, const std::string uav_name) { spawn_heading += randd(-3.14, 3.14); } - // create the inertia matrix - model_params_.J = Eigen::Matrix3d::Zero(); - model_params_.J(0, 0) = - model_params_.mass * (3.0 * model_params_.arm_length * model_params_.arm_length + model_params_.body_height * model_params_.body_height) / 12.0; - model_params_.J(1, 1) = - model_params_.mass * (3.0 * model_params_.arm_length * model_params_.arm_length + model_params_.body_height * model_params_.body_height) / 12.0; - model_params_.J(2, 2) = (model_params_.mass * model_params_.arm_length * model_params_.arm_length) / 2.0; + calculateInertia(model_params_); model_params_.allocation_matrix = param_loader.loadMatrixDynamic2(type + "/propulsion/allocation_matrix", 4, -1); @@ -214,6 +208,12 @@ UavSystemRos::UavSystemRos(ros::NodeHandle &nh, const std::string uav_name) { tf_broadcaster_ = std::make_shared(); + // | --------------------- service servers -------------------- | + + service_server_set_mass_ = nh.advertiseService(uav_name + "/set_mass", &UavSystemRos::callbackSetMass, this); + + service_server_set_ground_z_ = nh.advertiseService(uav_name + "/set_ground_z", &UavSystemRos::callbackSetGroundZ, this); + // | ------------------ first model iteration ----------------- | // * we need to iterate the model first to initialize its state @@ -657,6 +657,19 @@ double UavSystemRos::randd(double from, double to) { //} +/* calculateInertia() //{ */ + +void UavSystemRos::calculateInertia(MultirotorModel::ModelParams ¶ms) { + + // create the inertia matrix + params.J = Eigen::Matrix3d::Zero(); + params.J(0, 0) = params.mass * (3.0 * params.arm_length * params.arm_length + params.body_height * params.body_height) / 12.0; + params.J(1, 1) = params.mass * (3.0 * params.arm_length * params.arm_length + params.body_height * params.body_height) / 12.0; + params.J(2, 2) = (params.mass * params.arm_length * params.arm_length) / 2.0; +} + +//} + // | ------------------------ callbacks ----------------------- | /* callbackActuatorCmd() //{ */ @@ -1008,4 +1021,62 @@ void UavSystemRos::callbackTrackerCmd(const mrs_msgs::TrackerCommand::ConstPtr m //} +/* callbackSetMass() //{ */ + +bool UavSystemRos::callbackSetMass(mrs_msgs::Float64Srv::Request &req, mrs_msgs::Float64Srv::Response &res) { + + if (!is_initialized_) { + return false; + } + + { + std::scoped_lock lock(mutex_uav_system_); + + model_params_ = uav_system_.getParams(); + + const double original_mass = model_params_.mass; + + model_params_.mass = req.value; + + model_params_.allocation_matrix.row(2) = model_params_.mass * (model_params_.allocation_matrix.row(2) / original_mass); + + calculateInertia(model_params_); + + uav_system_.setParams(model_params_); + } + + res.success = true; + res.message = "mass set"; + + return true; +} + +//} + +/* callbackSetGroundZ() //{ */ + +bool UavSystemRos::callbackSetGroundZ(mrs_msgs::Float64Srv::Request &req, mrs_msgs::Float64Srv::Response &res) { + + if (!is_initialized_) { + return false; + } + + { + std::scoped_lock lock(mutex_uav_system_); + + model_params_ = uav_system_.getParams(); + + model_params_.ground_z = req.value; + + uav_system_.setParams(model_params_); + } + + res.success = true; + res.message = "ground z set"; + + return true; +} + +//} + } // namespace mrs_multirotor_simulator