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

[Aerial Robot Model][Underactuated][Plugin] fix the wrong args assignment for model constructor #561

Merged
merged 2 commits into from
Oct 11, 2023
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 @@ -36,7 +36,7 @@
#include <aerial_robot_model/model/plugin/multirotor_robot_model.h>

MultirotorRobotModel::MultirotorRobotModel(bool init_with_rosparam, bool verbose, double fc_t_min_thre, double epsilon):
RobotModel(init_with_rosparam, verbose, 0, fc_t_min_thre, epsilon)
RobotModel(init_with_rosparam, verbose, true, 0, fc_t_min_thre, epsilon)
{
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@
#include <aerial_robot_model/model/plugin/underactuated_tilted_robot_model.h>

UnderactuatedTiltedRobotModel::UnderactuatedTiltedRobotModel(bool init_with_rosparam, bool verbose, double fc_t_min_thre, double epsilon):
RobotModel(init_with_rosparam, verbose, fc_t_min_thre, 0, epsilon)
RobotModel(init_with_rosparam, verbose, true, 0, fc_t_min_thre, epsilon)
{

// calc static thrust
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -74,7 +74,7 @@ namespace aerial_robot_control
ros::Publisher interfrence_marker_pub_;

boost::shared_ptr<Dragon::FullVectoringRobotModel> dragon_robot_model_;
boost::shared_ptr<aerial_robot_model::RobotModel> robot_model_for_control_;
boost::shared_ptr<aerial_robot_model::transformable::RobotModel> robot_model_for_control_;
std::vector<float> target_base_thrust_;
std::vector<double> target_gimbal_angles_;
Eigen::VectorXd target_vectoring_f_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ namespace Dragon
virtual ~FullVectoringRobotModel() = default;


inline boost::shared_ptr<aerial_robot_model::RobotModel> getRobotModelForPlan() { return robot_model_for_plan_;}
inline boost::shared_ptr<aerial_robot_model::transformable::RobotModel> getRobotModelForPlan() { return robot_model_for_plan_;}
inline const Eigen::VectorXd& getHoverVectoringF() const {return hover_vectoring_f_;}

const std::vector<int> getRollLockedGimbal()
Expand Down Expand Up @@ -88,7 +88,7 @@ namespace Dragon

private:

boost::shared_ptr<aerial_robot_model::RobotModel> robot_model_for_plan_;
boost::shared_ptr<aerial_robot_model::transformable::RobotModel> robot_model_for_plan_;

Eigen::VectorXd hover_vectoring_f_;

Expand Down
2 changes: 1 addition & 1 deletion robots/dragon/src/control/full_vectoring_control.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ void DragonFullVectoringController::initialize(ros::NodeHandle nh, ros::NodeHand
rosParamInit();

dragon_robot_model_ = boost::dynamic_pointer_cast<Dragon::FullVectoringRobotModel>(robot_model);
robot_model_for_control_ = boost::make_shared<aerial_robot_model::RobotModel>();
robot_model_for_control_ = boost::make_shared<aerial_robot_model::transformable::RobotModel>();

/* initialize the gimbal target angles */
target_base_thrust_.resize(motor_num_);
Expand Down
2 changes: 1 addition & 1 deletion robots/dragon/src/model/full_vectoring_robot_model.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -82,7 +82,7 @@ FullVectoringRobotModel::FullVectoringRobotModel(bool init_with_rosparam, bool v
gimbal_roll_origin_from_cog_.resize(rotor_num);
setGimbalNominalAngles(std::vector<double>(0)); // for online initialize

robot_model_for_plan_ = boost::make_shared<aerial_robot_model::RobotModel>();
robot_model_for_plan_ = boost::make_shared<aerial_robot_model::transformable::RobotModel>();

if(debug_verbose_)
{
Expand Down
Loading