Skip to content

Commit

Permalink
Merge branch 'master' into ros-book
Browse files Browse the repository at this point in the history
  • Loading branch information
okalachev committed Oct 5, 2020
2 parents bb9d8ed + b36292c commit bcd7d15
Show file tree
Hide file tree
Showing 105 changed files with 11,454 additions and 102 deletions.
2 changes: 2 additions & 0 deletions .gitattributes
Original file line number Diff line number Diff line change
Expand Up @@ -4,3 +4,5 @@ eventemitter2.js linguist-vendored
ros3d.js linguist-vendored
three.min.js linguist-vendored
aruco_pose/vendor/* linguist-vendored
blockly/* linguist-vendored
highlight/* linguist-vendored
2 changes: 2 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -4,3 +4,5 @@
node_modules/
_book/
package-lock.json
clover_blocks/programs/*.*
!clover_blocks/programs/examples/*
2 changes: 1 addition & 1 deletion .travis.yml
Original file line number Diff line number Diff line change
Expand Up @@ -107,7 +107,7 @@ jobs:
- wget https://github.com/okalachev/editorconfig-checker/releases/download/1.2.1-disable-spaces-amount/ec-linux-amd64
- chmod +x ec-linux-amd64
script:
- ./ec-linux-amd64 -spaces-after-tabs -e "roslib.js|ros3d.js|eventemitter2.js|draw.cpp|BinUtils.swift|\.idea|apps/android/app|Assets.xcassets|test_parser_pass.txt|test_node_failure.txt|aruco_pose/vendor|\.stl|\.dxf|\.dae"
- ./ec-linux-amd64 -spaces-after-tabs -e "roslib.js|ros3d.js|eventemitter2.js|draw.cpp|BinUtils.swift|\.idea|apps/android/app|blockly/|clover_blocks/programs/|highlight/|python.js|Assets.xcassets|test_parser_pass.txt|test_node_failure.txt|aruco_pose/vendor|\.stl|\.dxf|\.dae"
stages:
- Build
# More info there
Expand Down
1 change: 1 addition & 0 deletions book.json
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@
"richquotes@https://github.com/okalachev/gitbook-plugin-richquotes.git",
"yametrika",
"anchors",
"collapsible-menu",
"validate-links",
"bulk-redirect@https://github.com/okalachev/gitbook-plugin-bulk-redirect.git",
"sitemap@https://github.com/okalachev/plugin-sitemap.git",
Expand Down
4 changes: 4 additions & 0 deletions clover/launch/clover.launch
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@
<arg name="aruco" default="false"/>
<arg name="rangefinder_vl53l1x" default="true"/>
<arg name="led" default="true"/>
<arg name="blocks" default="false"/>
<arg name="rc" default="true"/>
<arg name="shell" default="true"/>

Expand Down Expand Up @@ -81,6 +82,9 @@
<arg name="simulator" value="$(arg simulator)"/>
</include>

<!-- Clover Blocks -->
<node name="clover_blocks" pkg="clover_blocks" type="clover_blocks" output="screen" if="$(arg blocks)"/>

<!-- rc backend -->
<node name="rc" pkg="clover" type="rc" output="screen" if="$(arg rc)" clear_params="true">
<!-- Send fake GCS heartbeats. Set to "true" for upstream PX4 -->
Expand Down
111 changes: 82 additions & 29 deletions clover/src/simple_offboard.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,7 @@
#include <clover/SetRates.h>

using std::string;
using std::isnan;
using namespace geometry_msgs;
using namespace sensor_msgs;
using namespace clover;
Expand Down Expand Up @@ -507,25 +508,84 @@ bool serve(enum setpoint_type_t sp_type, float x, float y, float z, float vx, fl
if (busy)
throw std::runtime_error("Busy");

ENSURE_FINITE(x);
ENSURE_FINITE(y);
ENSURE_FINITE(z);
ENSURE_FINITE(vx);
ENSURE_FINITE(vy);
ENSURE_FINITE(vz);
ENSURE_FINITE(pitch);
ENSURE_FINITE(roll);
ENSURE_FINITE(pitch_rate);
ENSURE_FINITE(roll_rate);
ENSURE_FINITE(lat);
ENSURE_FINITE(lon);
ENSURE_FINITE(thrust);

busy = true;

// Checks
checkState();

// default frame is local frame
if (frame_id.empty())
frame_id = local_frame;

// look up for reference frame
auto search = reference_frames.find(frame_id);
const string& reference_frame = search == reference_frames.end() ? frame_id : search->second;

// Serve "partial" commands

if (!auto_arm && std::isfinite(yaw) &&
isnan(x) && isnan(y) && isnan(z) && isnan(vx) && isnan(vy) && isnan(vz) &&
isnan(pitch) && isnan(roll) && isnan(thrust) &&
isnan(lat) && isnan(lon)) {
// change only the yaw
if (setpoint_type == POSITION || setpoint_type == NAVIGATE || setpoint_type == NAVIGATE_GLOBAL || setpoint_type == VELOCITY) {
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);

message = "Changing yaw only";

QuaternionStamped q;
q.header.frame_id = frame_id;
q.header.stamp = stamp;
q.quaternion = tf::createQuaternionMsgFromYaw(yaw); // TODO: pitch=0, roll=0 is not totally correct
setpoint_position.pose.orientation = tf_buffer.transform(q, setpoint_position.header.frame_id).quaternion;
setpoint_yaw_type = YAW;
goto publish_setpoint;
} else {
throw std::runtime_error("Setting yaw is possible only when position or velocity setpoints active");
}
}

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) &&
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";

setpoint_yaw_type = YAW_RATE;
setpoint_yaw_rate = yaw_rate;
goto publish_setpoint;
} else {
throw std::runtime_error("Setting yaw rate is possible only when position or velocity setpoints active");
}
}

// Serve normal commands

if (sp_type == NAVIGATE || sp_type == POSITION) {
ENSURE_FINITE(x);
ENSURE_FINITE(y);
ENSURE_FINITE(z);
} else if (sp_type == NAVIGATE_GLOBAL) {
ENSURE_FINITE(lat);
ENSURE_FINITE(lon);
ENSURE_FINITE(z);
} else if (sp_type == VELOCITY) {
ENSURE_FINITE(vx);
ENSURE_FINITE(vy);
ENSURE_FINITE(vz);
} else if (sp_type == ATTITUDE) {
ENSURE_FINITE(pitch);
ENSURE_FINITE(roll);
ENSURE_FINITE(thrust);
} else if (sp_type == RATES) {
ENSURE_FINITE(pitch_rate);
ENSURE_FINITE(roll_rate);
ENSURE_FINITE(thrust);
}

if (sp_type == NAVIGATE || sp_type == NAVIGATE_GLOBAL) {
if (TIMEOUT(local_position, local_position_timeout))
throw std::runtime_error("No local position, check settings");
Expand All @@ -550,14 +610,6 @@ bool serve(enum setpoint_type_t sp_type, float x, float y, float z, float vx, fl
throw std::runtime_error("No global position");
}

// default frame is local frame
if (frame_id.empty())
frame_id = local_frame;

// look up for reference frame
auto search = reference_frames.find(frame_id);
const string& reference_frame = search == reference_frames.end() ? frame_id : search->second;

if (sp_type == NAVIGATE || sp_type == NAVIGATE_GLOBAL || sp_type == POSITION || sp_type == VELOCITY || sp_type == ATTITUDE) {
// make sure transform from frame_id to reference frame available
if (!waitTransform(reference_frame, frame_id, stamp, transform_timeout))
Expand Down Expand Up @@ -625,7 +677,7 @@ bool serve(enum setpoint_type_t sp_type, float x, float y, float z, float vx, fl
} else {
setpoint_yaw_type = YAW;
setpoint_yaw_rate = 0;
ps.pose.orientation = tf::createQuaternionMsgFromRollPitchYaw(roll, pitch, yaw);
ps.pose.orientation = tf::createQuaternionMsgFromYaw(yaw);
}

tf_buffer.transform(ps, setpoint_position, reference_frame);
Expand Down Expand Up @@ -653,6 +705,7 @@ bool serve(enum setpoint_type_t sp_type, float x, float y, float z, float vx, fl

wait_armed = auto_arm;

publish_setpoint:
publish(stamp); // calculate initial transformed messages first
setpoint_timer.start();

Expand Down Expand Up @@ -693,27 +746,27 @@ bool serve(enum setpoint_type_t sp_type, float x, float y, float z, float vx, fl
}

bool navigate(Navigate::Request& req, Navigate::Response& res) {
return serve(NAVIGATE, req.x, req.y, req.z, 0, 0, 0, 0, 0, req.yaw, 0, 0, req.yaw_rate, 0, 0, 0, req.speed, req.frame_id, req.auto_arm, res.success, res.message);
return serve(NAVIGATE, req.x, req.y, req.z, NAN, NAN, NAN, NAN, NAN, req.yaw, NAN, NAN, req.yaw_rate, NAN, NAN, NAN, req.speed, req.frame_id, req.auto_arm, res.success, res.message);
}

bool navigateGlobal(NavigateGlobal::Request& req, NavigateGlobal::Response& res) {
return serve(NAVIGATE_GLOBAL, 0, 0, req.z, 0, 0, 0, 0, 0, req.yaw, 0, 0, req.yaw_rate, req.lat, req.lon, 0, req.speed, req.frame_id, req.auto_arm, res.success, res.message);
return serve(NAVIGATE_GLOBAL, NAN, NAN, req.z, NAN, NAN, NAN, NAN, NAN, req.yaw, NAN, NAN, req.yaw_rate, req.lat, req.lon, NAN, req.speed, req.frame_id, req.auto_arm, res.success, res.message);
}

bool setPosition(SetPosition::Request& req, SetPosition::Response& res) {
return serve(POSITION, req.x, req.y, req.z, 0, 0, 0, 0, 0, req.yaw, 0, 0, req.yaw_rate, 0, 0, 0, 0, req.frame_id, req.auto_arm, res.success, res.message);
return serve(POSITION, req.x, req.y, req.z, NAN, NAN, NAN, NAN, NAN, req.yaw, NAN, NAN, req.yaw_rate, NAN, NAN, NAN, NAN, req.frame_id, req.auto_arm, res.success, res.message);
}

bool setVelocity(SetVelocity::Request& req, SetVelocity::Response& res) {
return serve(VELOCITY, 0, 0, 0, req.vx, req.vy, req.vz, 0, 0, req.yaw, 0, 0, req.yaw_rate, 0, 0, 0, 0, req.frame_id, req.auto_arm, res.success, res.message);
return serve(VELOCITY, NAN, NAN, NAN, req.vx, req.vy, req.vz, NAN, NAN, req.yaw, NAN, NAN, req.yaw_rate, NAN, NAN, NAN, NAN, req.frame_id, req.auto_arm, res.success, res.message);
}

bool setAttitude(SetAttitude::Request& req, SetAttitude::Response& res) {
return serve(ATTITUDE, 0, 0, 0, 0, 0, 0, req.pitch, req.roll, req.yaw, 0, 0, 0, 0, 0, req.thrust, 0, req.frame_id, req.auto_arm, res.success, res.message);
return serve(ATTITUDE, NAN, NAN, NAN, NAN, NAN, NAN, req.pitch, req.roll, req.yaw, NAN, NAN, NAN, NAN, NAN, req.thrust, NAN, req.frame_id, req.auto_arm, res.success, res.message);
}

bool setRates(SetRates::Request& req, SetRates::Response& res) {
return serve(RATES, 0, 0, 0, 0, 0, 0, 0, 0, 0, req.pitch_rate, req.roll_rate, req.yaw_rate, 0, 0, req.thrust, 0, "", req.auto_arm, res.success, res.message);
return serve(RATES, NAN, NAN, NAN, NAN, NAN, NAN, NAN, NAN, NAN, req.pitch_rate, req.roll_rate, req.yaw_rate, NAN, NAN, req.thrust, NAN, "", req.auto_arm, res.success, res.message);
}

bool land(std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& res)
Expand Down
1 change: 1 addition & 0 deletions clover/www/index.html
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@ <h1>Clover Drone Kit Tools</h1>
<li><a href="" id="butterfly">Open web terminal</a> (<code>Butterfly</code>)</li>
<li><a href="viz.html">View 3D visualization</a> (<code>ros3djs</code>)</li>
<li><a href="aruco_map.html">3D visualization for markers map</a> (<code>ros3djs</code>)</li>
<li><a href="../clover_blocks/">Blocks programming</a> (<code>Blockly</code>)</li>
</ul>

<div class="version"></div>
Expand Down
87 changes: 87 additions & 0 deletions clover_blocks/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,87 @@
cmake_minimum_required(VERSION 2.8.3)
project(clover_blocks)

find_package(catkin REQUIRED COMPONENTS message_generation)

add_message_files(
FILES
Prompt.msg
)

add_service_files(
FILES
Run.srv
Load.srv
Store.srv
)

generate_messages(
DEPENDENCIES
# std_msgs # Or other packages containing msgs
)

catkin_package(
# INCLUDE_DIRS include
# LIBRARIES roslaunch_editor
CATKIN_DEPENDS message_runtime
# DEPENDS system_lib
)

#############
## Install ##
#############

# all install targets should use catkin DESTINATION variables
# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html

## Mark executable scripts (Python etc.) for installation
## in contrast to setup.py, you can choose the destination
# install(PROGRAMS
# scripts/my_python_script
# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )

## Mark executables for installation
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html
# install(TARGETS ${PROJECT_NAME}_node
# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )

## Mark libraries for installation
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html
# install(TARGETS ${PROJECT_NAME}
# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}
# )

## Mark cpp header files for installation
# install(DIRECTORY include/${PROJECT_NAME}/
# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
# FILES_MATCHING PATTERN "*.h"
# PATTERN ".svn" EXCLUDE
# )

## Mark other files for installation (e.g. launch and bag files, etc.)
# install(FILES
# # myfile1
# # myfile2
# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
# )

catkin_install_python(PROGRAMS src/clover_blocks
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

#############
## Testing ##
#############

## Add gtest based cpp test target and link libraries
# catkin_add_gtest(${PROJECT_NAME}-test test/test_roslaunch_editor.cpp)
# if(TARGET ${PROJECT_NAME}-test)
# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
# endif()

## Add folders to be run by python nosetests
# catkin_add_nosetests(test)
52 changes: 52 additions & 0 deletions clover_blocks/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,52 @@
# clover_blocks

Blockly programming support for Clover.

<img src="screenshot.png" width=700>

See user documentation at the [main Clover documentation site](https://clover.coex.tech/en/blocks.html).

Internal package documentation is given below.

## Frontend

The frontend files are located in [`www`](./www/) subdirectory. The frontend application uses [`roblib.js`](http://wiki.ros.org/roslibjs) library for communicating with backend node and other ROS resources.

## `clover_blocks` node

`clover_blocks` is the blocks programming backend, implementing all the services and topics needed for running Blockly-generated Python script.

### Services

* `~run` ([*clover_blocks/Run*](srv/Run.srv)) – run Blockly-generated program (in Python).
* `~stop` ([*std_srvs/Trigger*](http://docs.ros.org/melodic/api/std_srvs/html/srv/Trigger.html)) – terminate the running program.
* `~store` ([*clover_blocks/load*](srv/Store.srv)) – store a user program (to `<package_path>/programs` by default).
* `~load` ([*clover_blocks/load*](srv/Load.srv)) – load all the stored programs.

### Parameters

* `~programs_dir` (*string*) – directory for user programs.

Parameters read by frontend:

* `~navigate_tolerance` (*float*) – distance tolerance in meters, used for navigate-like blocks (default: 0.2).
* `~sleep_time` (*float*) – duration of sleep in loop cycles, used for navigate-like blocks (default: 0.2).

These parameters also can be set as URL GET-parameters, for example:

```
http://<hostname>/clover_blocks/?navigate_tolerance=0.5&sleep_time=0.1
```

### Topics

#### Published

* `~running` ([*std_msgs/Bool*](http://docs.ros.org/melodic/api/std_msgs/html/msg/Bool.html)) – indicates if the program is currently running.
* `~block` ([*std_msgs/String*](http://docs.ros.org/melodic/api/std_msgs/html/msg/String.html)) – current executing block (maximum topic rate is limited).
* `~error` ([*std_msgs/String*](http://docs.ros.org/melodic/api/std_msgs/html/msg/String.html)) – user program errors and exceptions.
* `~prompt` ([*clover_blocks/Prompt*](msg/Prompt.msg)) – user input request (includes random request ID string).

This topic is published from the frontend side:

* `~prompt/<request_id>` ([*std_msgs/String*](http://docs.ros.org/melodic/api/std_msgs/html/msg/String.html)) – user input response.
2 changes: 2 additions & 0 deletions clover_blocks/msg/Prompt.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
string message # message for prompt
string id # user response should be published to ~input/<id> topic
Loading

0 comments on commit bcd7d15

Please sign in to comment.