mirror of
https://github.com/CopterExpress/clover.git
synced 2026-06-03 00:19:33 +00:00
Compare commits
6 Commits
bullseye
...
terrain-fr
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
aa89077c23 | ||
|
|
4e9d8a64d0 | ||
|
|
94171d51ac | ||
|
|
0d45b6cb7f | ||
|
|
eb448ae0e7 | ||
|
|
d61760a718 |
@@ -4,6 +4,8 @@
|
||||
<arg name="direction_z" default="down"/> <!-- direction the camera points: down, up -->
|
||||
<arg name="direction_y" default="backward"/> <!-- direction the camera cable points: backward, forward -->
|
||||
<arg name="device" default="/dev/video0"/> <!-- v4l2 device -->
|
||||
<arg name="throttled_topic" default="true"/> <!-- enable throttled image topic -->
|
||||
<arg name="throttled_topic_rate" default="5.0"/> <!-- throttled image topic rate -->
|
||||
<arg name="simulator" default="false"/>
|
||||
|
||||
<node if="$(eval direction_z == 'down' and direction_y == 'backward')" pkg="tf2_ros" type="static_transform_publisher" name="main_camera_frame" args="0.05 0 -0.07 -1.5707963 0 3.1415926 base_link main_camera_optical"/>
|
||||
@@ -43,4 +45,8 @@
|
||||
<node pkg="clover" type="camera_markers" ns="main_camera" name="main_camera_markers">
|
||||
<param name="scale" value="3.0"/>
|
||||
</node>
|
||||
|
||||
<!-- image topic throttled -->
|
||||
<node pkg="topic_tools" name="main_camera_throttle" type="throttle" ns="main_camera"
|
||||
args="messages image_raw $(arg throttled_topic_rate) image_raw_throttled" if="$(arg throttled_topic)"/>
|
||||
</launch>
|
||||
|
||||
@@ -37,6 +37,7 @@
|
||||
#include <mavros_msgs/State.h>
|
||||
#include <mavros_msgs/StatusText.h>
|
||||
#include <mavros_msgs/ManualControl.h>
|
||||
#include <mavros_msgs/Altitude.h>
|
||||
|
||||
#include <clover/GetTelemetry.h>
|
||||
#include <clover/Navigate.h>
|
||||
@@ -54,6 +55,7 @@ using namespace clover;
|
||||
using mavros_msgs::PositionTarget;
|
||||
using mavros_msgs::AttitudeTarget;
|
||||
using mavros_msgs::Thrust;
|
||||
using mavros_msgs::Altitude;
|
||||
|
||||
// tf2
|
||||
tf2_ros::Buffer tf_buffer;
|
||||
@@ -96,10 +98,12 @@ Thrust thrust_msg;
|
||||
TwistStamped rates_msg;
|
||||
TransformStamped target, setpoint;
|
||||
geometry_msgs::TransformStamped body;
|
||||
geometry_msgs::TransformStamped terrain;
|
||||
|
||||
// State
|
||||
PoseStamped nav_start;
|
||||
PoseStamped setpoint_position, setpoint_position_transformed;
|
||||
Vector3Stamped setpoint_z, setpoint_z_transformed; // for z-only commands
|
||||
Vector3Stamped setpoint_velocity, setpoint_velocity_transformed;
|
||||
QuaternionStamped setpoint_attitude, setpoint_attitude_transformed;
|
||||
float setpoint_yaw_rate;
|
||||
@@ -122,6 +126,8 @@ enum setpoint_type_t setpoint_type = NONE;
|
||||
|
||||
enum { YAW, YAW_RATE, TOWARDS } setpoint_yaw_type;
|
||||
|
||||
bool setpoint_z_valid = false;
|
||||
|
||||
// Last received telemetry messages
|
||||
mavros_msgs::State state;
|
||||
mavros_msgs::StatusText statustext;
|
||||
@@ -173,6 +179,15 @@ void handleLocalPosition(const PoseStamped& pose)
|
||||
// TODO: terrain?, home?
|
||||
}
|
||||
|
||||
void handleAltitude(const Altitude& alt)
|
||||
{
|
||||
// publish terrain frame
|
||||
if (!std::isfinite(alt.bottom_clearance)) return;
|
||||
terrain.header.stamp = alt.header.stamp;
|
||||
terrain.transform.translation.z = -alt.bottom_clearance;
|
||||
transform_broadcaster->sendTransform(terrain);
|
||||
}
|
||||
|
||||
// wait for transform without interrupting publishing setpoints
|
||||
inline bool waitTransform(const string& target, const string& source,
|
||||
const ros::Time& stamp, const ros::Duration& timeout) // editorconfig-checker-disable-line
|
||||
@@ -421,6 +436,18 @@ void publish(const ros::Time stamp)
|
||||
}
|
||||
}
|
||||
|
||||
if (setpoint_z_valid && setpoint_type == NAVIGATE || setpoint_type == NAVIGATE_GLOBAL || setpoint_type == POSITION) {
|
||||
setpoint_z.header.stamp = stamp;
|
||||
try {
|
||||
tf_buffer.transform(setpoint_z, setpoint_z_transformed, local_frame, ros::Duration(0.05));
|
||||
setpoint_position_transformed.pose.position.z = setpoint_z_transformed.vector.z;
|
||||
|
||||
} catch (const tf2::TransformException& e) {
|
||||
ROS_WARN_THROTTLE(10, "can't transform z coordinate from %s to %s, ignoring z coordinate",
|
||||
setpoint_z.header.frame_id.c_str(), local_frame.c_str());
|
||||
}
|
||||
}
|
||||
|
||||
if (setpoint_type == POSITION) {
|
||||
position_msg = setpoint_position_transformed;
|
||||
}
|
||||
@@ -556,7 +583,7 @@ bool serve(enum setpoint_type_t sp_type, float x, float y, float z, float vx, fl
|
||||
|
||||
// look up for reference frame
|
||||
auto search = reference_frames.find(frame_id);
|
||||
const string& reference_frame = search == reference_frames.end() ? frame_id : search->second;
|
||||
const string& reference_frame = search == reference_frames.end() ? frame_id : search->second; // when not found it's the same frame
|
||||
|
||||
// Serve "partial" commands
|
||||
|
||||
@@ -583,22 +610,33 @@ bool serve(enum setpoint_type_t sp_type, float x, float y, float z, float vx, fl
|
||||
}
|
||||
}
|
||||
|
||||
if (!auto_arm && std::isfinite(yaw_rate) &&
|
||||
isnan(x) && isnan(y) && isnan(z) && isnan(vx) && isnan(vy) && isnan(vz) &&
|
||||
isnan(pitch) && isnan(roll) && isnan(yaw) && isnan(thrust) &&
|
||||
if (!auto_arm && std::isfinite(z) &&
|
||||
isnan(x) && isnan(y) && isnan(vx) && isnan(vy) && isnan(vz) &&
|
||||
isnan(pitch) && isnan(roll) && isnan(thrust) &&
|
||||
isnan(lat) && isnan(lon)) {
|
||||
// change only the yaw rate
|
||||
if (setpoint_type == POSITION || setpoint_type == NAVIGATE || setpoint_type == NAVIGATE_GLOBAL || setpoint_type == VELOCITY) {
|
||||
message = "Changing yaw rate only";
|
||||
// set only the z
|
||||
if (setpoint_type == POSITION || setpoint_type == NAVIGATE || setpoint_type == NAVIGATE_GLOBAL) {
|
||||
if (!waitTransform(setpoint_position.header.frame_id, frame_id, stamp, transform_timeout))
|
||||
throw std::runtime_error("Can't transform from " + frame_id + " to " + setpoint_position.header.frame_id);
|
||||
|
||||
setpoint_yaw_type = YAW_RATE;
|
||||
setpoint_yaw_rate = yaw_rate;
|
||||
message = "Changing z only";
|
||||
|
||||
setpoint_z.header.frame_id = frame_id;
|
||||
setpoint_z.header.stamp = stamp;
|
||||
setpoint_z.vector.z = z;
|
||||
setpoint_z_valid = true;
|
||||
goto publish_setpoint;
|
||||
|
||||
} else {
|
||||
throw std::runtime_error("Setting yaw rate is possible only when position or velocity setpoints active");
|
||||
throw std::runtime_error("Setting z is possible only when position setpoint active");
|
||||
}
|
||||
}
|
||||
|
||||
// commands without z
|
||||
if (isnan(z) && setpoint_z_valid && (sp_type == NAVIGATE || sp_type == NAVIGATE_GLOBAL || sp_type == POSITION)) {
|
||||
z = 0;
|
||||
}
|
||||
|
||||
// Serve normal commands
|
||||
|
||||
if (sp_type == NAVIGATE || sp_type == POSITION) {
|
||||
@@ -860,6 +898,13 @@ bool land(std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& res)
|
||||
return false;
|
||||
}
|
||||
|
||||
bool release(std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& res)
|
||||
{
|
||||
setpoint_timer.stop();
|
||||
res.success = true;
|
||||
return true;
|
||||
}
|
||||
|
||||
int main(int argc, char **argv)
|
||||
{
|
||||
ros::init(argc, argv, "simple_offboard");
|
||||
@@ -881,6 +926,7 @@ int main(int argc, char **argv)
|
||||
nh_priv.param("check_kill_switch", check_kill_switch, true);
|
||||
nh_priv.param("default_speed", default_speed, 0.5f);
|
||||
nh_priv.param<string>("body_frame", body.child_frame_id, "body");
|
||||
nh_priv.param<string>("terrain_frame", terrain.child_frame_id, "terrain");
|
||||
nh_priv.getParam("reference_frames", reference_frames);
|
||||
|
||||
// Default reference frames
|
||||
@@ -916,6 +962,13 @@ int main(int argc, char **argv)
|
||||
auto manual_control_sub = nh.subscribe(mavros + "/manual_control/control", 1, &handleMessage<mavros_msgs::ManualControl, manual_control>);
|
||||
auto local_position_sub = nh.subscribe(mavros + "/local_position/pose", 1, &handleLocalPosition);
|
||||
|
||||
ros::Subscriber altitude_sub;
|
||||
if (!body.child_frame_id.empty() && !terrain.child_frame_id.empty()) {
|
||||
terrain.header.frame_id = body.child_frame_id;
|
||||
terrain.transform.rotation = tf::createQuaternionMsgFromRollPitchYaw(0, 0, 0);
|
||||
altitude_sub = nh.subscribe(mavros + "/altitude", 1, &handleAltitude);
|
||||
}
|
||||
|
||||
// Setpoint publishers
|
||||
position_pub = nh.advertise<PoseStamped>(mavros + "/setpoint_position/local", 1);
|
||||
position_raw_pub = nh.advertise<PositionTarget>(mavros + "/setpoint_raw/local", 1);
|
||||
@@ -933,6 +986,7 @@ int main(int argc, char **argv)
|
||||
auto sa_serv = nh.advertiseService("set_attitude", &setAttitude);
|
||||
auto sr_serv = nh.advertiseService("set_rates", &setRates);
|
||||
auto ld_serv = nh.advertiseService("land", &land);
|
||||
auto rl_serv = nh_priv.advertiseService("release", &release);
|
||||
|
||||
// Setpoint timer
|
||||
setpoint_timer = nh.createTimer(ros::Duration(1 / nh_priv.param("setpoint_rate", 30.0)), &publishSetpoint, false, false);
|
||||
|
||||
@@ -24,6 +24,7 @@ def test_simple_offboard_services_available():
|
||||
rospy.wait_for_service('set_attitude', timeout=5)
|
||||
rospy.wait_for_service('set_rates', timeout=5)
|
||||
rospy.wait_for_service('land', timeout=5)
|
||||
rospy.wait_for_service('simple_offboard/release', timeout=5)
|
||||
|
||||
def test_web_video_server(node):
|
||||
try:
|
||||
|
||||
@@ -37,6 +37,9 @@
|
||||
|
||||
<node name="clover_blocks" pkg="clover_blocks" type="clover_blocks" output="screen" required="true"/>
|
||||
|
||||
<node pkg="topic_tools" name="main_camera_throttle" type="throttle" ns="main_camera"
|
||||
args="messages image_raw 5.0 image_raw_throttled" required="true"/>
|
||||
|
||||
<param name="test_module" value="$(find clover)/test/basic.py"/>
|
||||
<test test-name="basic_test" pkg="ros_pytest" type="ros_pytest_runner"/>
|
||||
</launch>
|
||||
|
||||
@@ -145,6 +145,8 @@ rospy.spin()
|
||||
|
||||
The script will take up to 100% CPU capacity. To slow down the script artificially, you can use [throttling](http://wiki.ros.org/topic_tools/throttle) of frames from the camera, for example, at 5 Hz (`main_camera.launch`):
|
||||
|
||||
> **Note** Starting from [image](image.md) version **0.24** `image_raw_throttled` topic is available without addition configuration.
|
||||
|
||||
```xml
|
||||
<node pkg="topic_tools" name="cam_throttle" type="throttle"
|
||||
args="messages main_camera/image_raw 5.0 main_camera/image_raw_throttled"/>
|
||||
|
||||
@@ -305,6 +305,16 @@ rosservice call /land "{}"
|
||||
|
||||
> **Caution** In recent PX4 versions, the vehicle will be switched out of LAND mode to manual mode, if the remote control sticks are moved significantly.
|
||||
|
||||
### release
|
||||
|
||||
If it's necessary to pause sending setpoint messages, use the `simple_offboard/release` service:
|
||||
|
||||
```python
|
||||
release = rospy.ServiceProxy('simple_offboard/release', Trigger)
|
||||
|
||||
release()
|
||||
```
|
||||
|
||||
## Additional materials
|
||||
|
||||
* [ArUco-based position estimation and navigation](aruco.md).
|
||||
|
||||
@@ -147,6 +147,8 @@ rospy.spin()
|
||||
|
||||
Скрипт будет занимать 100% процессора. Для искусственного замедления работы скрипта можно запустить [throttling](http://wiki.ros.org/topic_tools/throttle) кадров с камеры, например, в 5 Гц (`main_camera.launch`):
|
||||
|
||||
> **Note** Начиная с версии [образа](image.md) **0.24** топик `image_raw_throttled` доступен без дополнительной конфигурации.
|
||||
|
||||
```xml
|
||||
<node pkg="topic_tools" name="cam_throttle" type="throttle"
|
||||
args="messages main_camera/image_raw 5.0 main_camera/image_raw_throttled"/>
|
||||
|
||||
@@ -305,6 +305,16 @@ rosservice call /land "{}"
|
||||
|
||||
> **Caution** В более новых версиях PX4 коптер выйдет из режима LAND в ручной режим, если сильно перемещать стики.
|
||||
|
||||
### release
|
||||
|
||||
В случае необходимости приостановки отправки setpoint-сообщений, используйте сервис `simple_offboard/release`:
|
||||
|
||||
```python
|
||||
release = rospy.ServiceProxy('simple_offboard/release', Trigger)
|
||||
|
||||
release()
|
||||
```
|
||||
|
||||
## Дополнительные материалы
|
||||
|
||||
* [Полеты в поле ArUco-маркеров](aruco.md).
|
||||
|
||||
Reference in New Issue
Block a user