49 std::vector<double> rotor_positions(3 *
num_rotors_);
50 std::vector<double> rotor_vector_normal(3 *
num_rotors_);
51 std::vector<int> rotor_rotation_directions(
num_rotors_);
75 for (
int j = 0; j < 3; j++)
77 motors_[
i].position(j) = rotor_positions[3*
i + j];
78 motors_[
i].normal(j) = rotor_vector_normal[3*
i + j];
81 motors_[
i].direction = rotor_rotation_directions[
i];
83 Eigen::Vector3d moment_from_thrust =
motors_[
i].position.cross(
motors_[
i].normal);
84 Eigen::Vector3d moment_from_torque =
motors_[
i].direction *
motors_[
i].normal;
114 wind_ = Eigen::Vector3d::Zero();
123 return Eigen::Matrix<double, 6, 1>::Zero();
127 double pd = x.
pos[2];
130 Eigen::Vector3d Va = x.
vel + x.
rot.inverse()*
wind_;
136 double signal = act_cmds[
i];
142 double alpha = dt/(tau + dt);
150 Eigen::Vector4d output_forces_and_torques = output_forces + output_torques;
156 Eigen::Matrix<double, 6,1> forces;
160 forces.block<3,1>(3,0) = -
angular_mu_ * x.
omega + output_forces_and_torques.block<3,1>(0,0);
163 forces(2) += output_forces_and_torques(3) - ground_effect;
Eigen::Matrix< double, 6, 1 > updateForcesAndTorques(Current_State x, const int act_cmds[])
Eigen::VectorXd desired_forces_
Eigen::VectorXd actual_torques_
Eigen::VectorXd actual_forces_
Multirotor(ros::NodeHandle *nh)
#define ROS_ASSERT_MSG(cond,...)
std::vector< double > ground_effect_
const std::string & getNamespace() const
std::vector< Motor > motors_
TFSIMD_FORCE_INLINE const tfScalar & z() const
double sat(double x, double max, double min)
#define ROS_INFO_STREAM(args)
bool getParam(const std::string &key, std::string &s) const
std::vector< double > T_poly
double max(double x, double y)
void set_wind(Eigen::Vector3d wind)
Eigen::MatrixXd force_allocation_matrix_
Eigen::MatrixXd torque_allocation_matrix_
std::vector< double > F_poly
Eigen::VectorXd desired_torques_