diff --git a/aerial_robot_model/include/aerial_robot_model/model/aerial_robot_model_ros.h b/aerial_robot_model/include/aerial_robot_model/model/aerial_robot_model_ros.h index 3b9fc9c7b..06682d28b 100644 --- a/aerial_robot_model/include/aerial_robot_model/model/aerial_robot_model_ros.h +++ b/aerial_robot_model/include/aerial_robot_model/model/aerial_robot_model_ros.h @@ -37,8 +37,8 @@ #include #include +#include #include -#include #include #include #include @@ -74,6 +74,6 @@ namespace aerial_robot_model { //private functions void jointStateCallback(const sensor_msgs::JointStateConstPtr& state); bool addExtraModuleCallback(aerial_robot_model::AddExtraModule::Request& req, aerial_robot_model::AddExtraModule::Response& res); - void desireCoordinateCallback(const spinal::DesireCoordConstPtr& msg); + void desireCoordinateCallback(const geometry_msgs::QuaternionConstPtr& msg); }; } //namespace aerial_robot_model diff --git a/aerial_robot_model/src/model/base_model/robot_model_ros.cpp b/aerial_robot_model/src/model/base_model/robot_model_ros.cpp index 77de238e2..8bc0fd59a 100644 --- a/aerial_robot_model/src/model/base_model/robot_model_ros.cpp +++ b/aerial_robot_model/src/model/base_model/robot_model_ros.cpp @@ -91,8 +91,9 @@ namespace aerial_robot_model { return false; } - void RobotModelRos::desireCoordinateCallback(const spinal::DesireCoordConstPtr& msg) + void RobotModelRos::desireCoordinateCallback(const geometry_msgs::QuaternionConstPtr& msg) { - robot_model_->setCogDesireOrientation(msg->roll, msg->pitch, msg->yaw); + KDL::Rotation rot = KDL::Rotation::Quaternion(msg->x, msg->y, msg->z, msg->w); + robot_model_->setCogDesireOrientation(rot); } } //namespace aerial_robot_model diff --git a/aerial_robot_model/test/aerial_robot_model/numerical_jacobians.cpp b/aerial_robot_model/test/aerial_robot_model/numerical_jacobians.cpp index 9074c1104..f16643f23 100644 --- a/aerial_robot_model/test/aerial_robot_model/numerical_jacobians.cpp +++ b/aerial_robot_model/test/aerial_robot_model/numerical_jacobians.cpp @@ -28,9 +28,10 @@ namespace aerial_robot_model { nhp_.param("feasible_control_torque_diff_thre", feasible_control_torque_diff_thre_, 0.001); } - void NumericalJacobian::desireCoordinateCallback(const spinal::DesireCoordConstPtr& msg) + void NumericalJacobian::desireCoordinateCallback(const geometry_msgs::QuaternionConstPtr& msg) { - getRobotModel().setCogDesireOrientation(msg->roll, msg->pitch, msg->yaw); + KDL::Rotation rot = KDL::Rotation::Quaternion(msg->x, msg->y, msg->z, msg->w); + getRobotModel().setCogDesireOrientation(rot); } void NumericalJacobian::jointStateCallback(const sensor_msgs::JointStateConstPtr& state) diff --git a/aerial_robot_model/test/aerial_robot_model/numerical_jacobians.h b/aerial_robot_model/test/aerial_robot_model/numerical_jacobians.h index db36896b2..d48df848e 100644 --- a/aerial_robot_model/test/aerial_robot_model/numerical_jacobians.h +++ b/aerial_robot_model/test/aerial_robot_model/numerical_jacobians.h @@ -36,7 +36,7 @@ #pragma once #include -#include +#include namespace aerial_robot_model { @@ -82,7 +82,7 @@ namespace aerial_robot_model { aerial_robot_model::transformable::RobotModel& getRobotModel() const { return *robot_model_; } void jointStateCallback(const sensor_msgs::JointStateConstPtr& state); - void desireCoordinateCallback(const spinal::DesireCoordConstPtr& msg); + void desireCoordinateCallback(const geometry_msgs::QuaternionConstPtr& msg); // numerical solution virtual const Eigen::MatrixXd thrustForceNumericalJacobian(std::vector joint_indices);