Skip to content

Commit

Permalink
[Gimbalrotor][Model] delete unused fuction for mask calculation.
Browse files Browse the repository at this point in the history
  • Loading branch information
sugihara committed May 9, 2023
1 parent 11203c4 commit 47b4b05
Show file tree
Hide file tree
Showing 2 changed files with 0 additions and 28 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -14,21 +14,17 @@ class GimbalrotorRobotModel : public aerial_robot_model::RobotModel{
double epsilon = 10);
virtual ~GimbalrotorRobotModel() = default;

std::vector<Eigen::MatrixXd> getRotorMasks() { return rotor_masks_;};
template <class T> std::vector<T> getLinksRotationFromCog();
template <class T> std::vector<T> getThrustCoordRot();

private:
void updateRobotModelImpl(const KDL::JntArray& joint_positions) override;
void calcThrustMask();

std::vector<Eigen::MatrixXd> rotor_masks_;
KDL::JntArray gimbal_processed_joint_;
std::vector<KDL::Rotation> links_rotation_from_cog_;
std::vector<KDL::Rotation> thrust_coords_rot_;
std::mutex links_rotation_mutex_;
std::mutex thrust_rotation_mutex_;
bool mask_calc_flag_;

};

Expand Down
24 changes: 0 additions & 24 deletions robots/gimbalrotor/src/model/gimbalrotor_robot_model.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,30 +8,6 @@ GimbalrotorRobotModel::GimbalrotorRobotModel(bool init_with_rosparam, bool verbo

links_rotation_from_cog_.resize(rotor_num);
thrust_coords_rot_.resize(rotor_num);
mask_calc_flag_ = false;
}

void GimbalrotorRobotModel::calcThrustMask()
{
if(mask_calc_flag_) return;
/* this process is only for untransformable robots */
const auto& segment_map = getTree().getSegments();
const auto& joint_names = getJointNames();
const auto& joint_segment_map = getJointSegmentMap();
rotor_masks_.resize(RobotModel::getRotorNum());
for (int i = 0; i < joint_names.size(); i++)
{
Eigen::MatrixXd mask(3, 2);
std::vector<std::string> joint_i_child_segments = joint_segment_map.at(joint_names[i]);
std::string joint_i_child_segment_name = joint_i_child_segments.at(0);
const KDL::Segment& joint_i_child_segment = GetTreeElementSegment(segment_map.at(joint_i_child_segment_name));
Eigen::Vector3d gimbal_i_axis = aerial_robot_model::kdlToEigen(joint_i_child_segment.getJoint().JointAxis()); //supposing that the axis of gimbal is along coordinate axis
double m_00 = 1.0 - std::abs(gimbal_i_axis[0]);
double m_10 = 1.0 - std::abs(gimbal_i_axis[1]);
mask << m_00, 0, m_10, 0, 0, 1;
rotor_masks_[i] = mask;
}
mask_calc_flag_ = true;
}

void GimbalrotorRobotModel::updateRobotModelImpl(const KDL::JntArray& joint_positions)
Expand Down

0 comments on commit 47b4b05

Please sign in to comment.