mirror of
https://gitee.com/xiaohuolufeihua/bizhang_-obav.git
synced 2026-05-21 01:12:11 +00:00
ros offboard attitude sp demo: move attitude
This commit is contained in:
@@ -19,6 +19,7 @@ find_package(catkin REQUIRED COMPONENTS
|
|||||||
sensor_msgs
|
sensor_msgs
|
||||||
mav_msgs
|
mav_msgs
|
||||||
libmavconn
|
libmavconn
|
||||||
|
tf
|
||||||
)
|
)
|
||||||
find_package(Eigen REQUIRED)
|
find_package(Eigen REQUIRED)
|
||||||
|
|
||||||
|
|||||||
@@ -45,11 +45,13 @@
|
|||||||
<build_depend>std_msgs</build_depend>
|
<build_depend>std_msgs</build_depend>
|
||||||
<build_depend>eigen</build_depend>
|
<build_depend>eigen</build_depend>
|
||||||
<build_depend>libmavconn</build_depend>
|
<build_depend>libmavconn</build_depend>
|
||||||
|
<build_depend>tf</build_depend>
|
||||||
<run_depend>roscpp</run_depend>
|
<run_depend>roscpp</run_depend>
|
||||||
<run_depend>rospy</run_depend>
|
<run_depend>rospy</run_depend>
|
||||||
<run_depend>std_msgs</run_depend>
|
<run_depend>std_msgs</run_depend>
|
||||||
<run_depend>eigen</run_depend>
|
<run_depend>eigen</run_depend>
|
||||||
<run_depend>libmavconn</run_depend>
|
<run_depend>libmavconn</run_depend>
|
||||||
|
<run_depend>tf</run_depend>
|
||||||
|
|
||||||
|
|
||||||
<!-- The export tag contains other, unspecified, tags -->
|
<!-- The export tag contains other, unspecified, tags -->
|
||||||
|
|||||||
@@ -45,6 +45,7 @@
|
|||||||
#include <geometry_msgs/PoseStamped.h>
|
#include <geometry_msgs/PoseStamped.h>
|
||||||
#include <std_msgs/Float64.h>
|
#include <std_msgs/Float64.h>
|
||||||
#include <math.h>
|
#include <math.h>
|
||||||
|
#include <tf/transform_datatypes.h>
|
||||||
|
|
||||||
DemoOffboardAttitudeSetpoints::DemoOffboardAttitudeSetpoints() :
|
DemoOffboardAttitudeSetpoints::DemoOffboardAttitudeSetpoints() :
|
||||||
_n(),
|
_n(),
|
||||||
@@ -64,13 +65,13 @@ int DemoOffboardAttitudeSetpoints::main()
|
|||||||
|
|
||||||
/* Publish example offboard attitude setpoint */
|
/* Publish example offboard attitude setpoint */
|
||||||
geometry_msgs::PoseStamped pose;
|
geometry_msgs::PoseStamped pose;
|
||||||
pose.pose.position.x = 0;
|
tf::Quaternion q = tf::createQuaternionFromRPY(0.0, 0.1 * (sinf(0.5 * (float)px4::get_time_micros() / 1000000.0f)) , 0.0);
|
||||||
pose.pose.position.y = 0;
|
quaternionTFToMsg(q, pose.pose.orientation);
|
||||||
pose.pose.position.z = 1;
|
|
||||||
_attitude_sp_pub.publish(pose);
|
_attitude_sp_pub.publish(pose);
|
||||||
|
|
||||||
std_msgs::Float64 thrust;
|
std_msgs::Float64 thrust;
|
||||||
thrust.data = 0.4f + 0.25 * (sinf(2.0f * (float)px4::get_time_micros() / 1000000.0f)); // just some example throttle input that makes the quad 'jump'
|
thrust.data = 0.4f + 0.25 * (sinf((float)px4::get_time_micros() / 1000000.0f)); // just some example throttle input that makes the quad 'jump'
|
||||||
_thrust_sp_pub.publish(thrust);
|
_thrust_sp_pub.publish(thrust);
|
||||||
}
|
}
|
||||||
return 0;
|
return 0;
|
||||||
|
|||||||
Reference in New Issue
Block a user