Skip to content

Commit bcd7d15

Browse files
committed
Merge branch 'master' into ros-book
2 parents bb9d8ed + b36292c commit bcd7d15

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

105 files changed

+11454
-102
lines changed

.gitattributes

+2
Original file line numberDiff line numberDiff line change
@@ -4,3 +4,5 @@ eventemitter2.js linguist-vendored
44
ros3d.js linguist-vendored
55
three.min.js linguist-vendored
66
aruco_pose/vendor/* linguist-vendored
7+
blockly/* linguist-vendored
8+
highlight/* linguist-vendored

.gitignore

+2
Original file line numberDiff line numberDiff line change
@@ -4,3 +4,5 @@
44
node_modules/
55
_book/
66
package-lock.json
7+
clover_blocks/programs/*.*
8+
!clover_blocks/programs/examples/*

.travis.yml

+1-1
Original file line numberDiff line numberDiff line change
@@ -107,7 +107,7 @@ jobs:
107107
- wget https://github.com/okalachev/editorconfig-checker/releases/download/1.2.1-disable-spaces-amount/ec-linux-amd64
108108
- chmod +x ec-linux-amd64
109109
script:
110-
- ./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"
110+
- ./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"
111111
stages:
112112
- Build
113113
# More info there

book.json

+1
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,7 @@
99
"richquotes@https://github.com/okalachev/gitbook-plugin-richquotes.git",
1010
"yametrika",
1111
"anchors",
12+
"collapsible-menu",
1213
"validate-links",
1314
"bulk-redirect@https://github.com/okalachev/gitbook-plugin-bulk-redirect.git",
1415
"sitemap@https://github.com/okalachev/plugin-sitemap.git",

clover/launch/clover.launch

+4
Original file line numberDiff line numberDiff line change
@@ -10,6 +10,7 @@
1010
<arg name="aruco" default="false"/>
1111
<arg name="rangefinder_vl53l1x" default="true"/>
1212
<arg name="led" default="true"/>
13+
<arg name="blocks" default="false"/>
1314
<arg name="rc" default="true"/>
1415
<arg name="shell" default="true"/>
1516

@@ -81,6 +82,9 @@
8182
<arg name="simulator" value="$(arg simulator)"/>
8283
</include>
8384

85+
<!-- Clover Blocks -->
86+
<node name="clover_blocks" pkg="clover_blocks" type="clover_blocks" output="screen" if="$(arg blocks)"/>
87+
8488
<!-- rc backend -->
8589
<node name="rc" pkg="clover" type="rc" output="screen" if="$(arg rc)" clear_params="true">
8690
<!-- Send fake GCS heartbeats. Set to "true" for upstream PX4 -->

clover/src/simple_offboard.cpp

+82-29
Original file line numberDiff line numberDiff line change
@@ -46,6 +46,7 @@
4646
#include <clover/SetRates.h>
4747

4848
using std::string;
49+
using std::isnan;
4950
using namespace geometry_msgs;
5051
using namespace sensor_msgs;
5152
using namespace clover;
@@ -507,25 +508,84 @@ bool serve(enum setpoint_type_t sp_type, float x, float y, float z, float vx, fl
507508
if (busy)
508509
throw std::runtime_error("Busy");
509510

510-
ENSURE_FINITE(x);
511-
ENSURE_FINITE(y);
512-
ENSURE_FINITE(z);
513-
ENSURE_FINITE(vx);
514-
ENSURE_FINITE(vy);
515-
ENSURE_FINITE(vz);
516-
ENSURE_FINITE(pitch);
517-
ENSURE_FINITE(roll);
518-
ENSURE_FINITE(pitch_rate);
519-
ENSURE_FINITE(roll_rate);
520-
ENSURE_FINITE(lat);
521-
ENSURE_FINITE(lon);
522-
ENSURE_FINITE(thrust);
523-
524511
busy = true;
525512

526513
// Checks
527514
checkState();
528515

516+
// default frame is local frame
517+
if (frame_id.empty())
518+
frame_id = local_frame;
519+
520+
// look up for reference frame
521+
auto search = reference_frames.find(frame_id);
522+
const string& reference_frame = search == reference_frames.end() ? frame_id : search->second;
523+
524+
// Serve "partial" commands
525+
526+
if (!auto_arm && std::isfinite(yaw) &&
527+
isnan(x) && isnan(y) && isnan(z) && isnan(vx) && isnan(vy) && isnan(vz) &&
528+
isnan(pitch) && isnan(roll) && isnan(thrust) &&
529+
isnan(lat) && isnan(lon)) {
530+
// change only the yaw
531+
if (setpoint_type == POSITION || setpoint_type == NAVIGATE || setpoint_type == NAVIGATE_GLOBAL || setpoint_type == VELOCITY) {
532+
if (!waitTransform(setpoint_position.header.frame_id, frame_id, stamp, transform_timeout))
533+
throw std::runtime_error("Can't transform from " + frame_id + " to " + setpoint_position.header.frame_id);
534+
535+
message = "Changing yaw only";
536+
537+
QuaternionStamped q;
538+
q.header.frame_id = frame_id;
539+
q.header.stamp = stamp;
540+
q.quaternion = tf::createQuaternionMsgFromYaw(yaw); // TODO: pitch=0, roll=0 is not totally correct
541+
setpoint_position.pose.orientation = tf_buffer.transform(q, setpoint_position.header.frame_id).quaternion;
542+
setpoint_yaw_type = YAW;
543+
goto publish_setpoint;
544+
} else {
545+
throw std::runtime_error("Setting yaw is possible only when position or velocity setpoints active");
546+
}
547+
}
548+
549+
if (!auto_arm && std::isfinite(yaw_rate) &&
550+
isnan(x) && isnan(y) && isnan(z) && isnan(vx) && isnan(vy) && isnan(vz) &&
551+
isnan(pitch) && isnan(roll) && isnan(yaw) && isnan(thrust) &&
552+
isnan(lat) && isnan(lon)) {
553+
// change only the yaw rate
554+
if (setpoint_type == POSITION || setpoint_type == NAVIGATE || setpoint_type == NAVIGATE_GLOBAL || setpoint_type == VELOCITY) {
555+
message = "Changing yaw rate only";
556+
557+
setpoint_yaw_type = YAW_RATE;
558+
setpoint_yaw_rate = yaw_rate;
559+
goto publish_setpoint;
560+
} else {
561+
throw std::runtime_error("Setting yaw rate is possible only when position or velocity setpoints active");
562+
}
563+
}
564+
565+
// Serve normal commands
566+
567+
if (sp_type == NAVIGATE || sp_type == POSITION) {
568+
ENSURE_FINITE(x);
569+
ENSURE_FINITE(y);
570+
ENSURE_FINITE(z);
571+
} else if (sp_type == NAVIGATE_GLOBAL) {
572+
ENSURE_FINITE(lat);
573+
ENSURE_FINITE(lon);
574+
ENSURE_FINITE(z);
575+
} else if (sp_type == VELOCITY) {
576+
ENSURE_FINITE(vx);
577+
ENSURE_FINITE(vy);
578+
ENSURE_FINITE(vz);
579+
} else if (sp_type == ATTITUDE) {
580+
ENSURE_FINITE(pitch);
581+
ENSURE_FINITE(roll);
582+
ENSURE_FINITE(thrust);
583+
} else if (sp_type == RATES) {
584+
ENSURE_FINITE(pitch_rate);
585+
ENSURE_FINITE(roll_rate);
586+
ENSURE_FINITE(thrust);
587+
}
588+
529589
if (sp_type == NAVIGATE || sp_type == NAVIGATE_GLOBAL) {
530590
if (TIMEOUT(local_position, local_position_timeout))
531591
throw std::runtime_error("No local position, check settings");
@@ -550,14 +610,6 @@ bool serve(enum setpoint_type_t sp_type, float x, float y, float z, float vx, fl
550610
throw std::runtime_error("No global position");
551611
}
552612

553-
// default frame is local frame
554-
if (frame_id.empty())
555-
frame_id = local_frame;
556-
557-
// look up for reference frame
558-
auto search = reference_frames.find(frame_id);
559-
const string& reference_frame = search == reference_frames.end() ? frame_id : search->second;
560-
561613
if (sp_type == NAVIGATE || sp_type == NAVIGATE_GLOBAL || sp_type == POSITION || sp_type == VELOCITY || sp_type == ATTITUDE) {
562614
// make sure transform from frame_id to reference frame available
563615
if (!waitTransform(reference_frame, frame_id, stamp, transform_timeout))
@@ -625,7 +677,7 @@ bool serve(enum setpoint_type_t sp_type, float x, float y, float z, float vx, fl
625677
} else {
626678
setpoint_yaw_type = YAW;
627679
setpoint_yaw_rate = 0;
628-
ps.pose.orientation = tf::createQuaternionMsgFromRollPitchYaw(roll, pitch, yaw);
680+
ps.pose.orientation = tf::createQuaternionMsgFromYaw(yaw);
629681
}
630682

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

654706
wait_armed = auto_arm;
655707

708+
publish_setpoint:
656709
publish(stamp); // calculate initial transformed messages first
657710
setpoint_timer.start();
658711

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

695748
bool navigate(Navigate::Request& req, Navigate::Response& res) {
696-
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);
749+
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);
697750
}
698751

699752
bool navigateGlobal(NavigateGlobal::Request& req, NavigateGlobal::Response& res) {
700-
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);
753+
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);
701754
}
702755

703756
bool setPosition(SetPosition::Request& req, SetPosition::Response& res) {
704-
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);
757+
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);
705758
}
706759

707760
bool setVelocity(SetVelocity::Request& req, SetVelocity::Response& res) {
708-
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);
761+
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);
709762
}
710763

711764
bool setAttitude(SetAttitude::Request& req, SetAttitude::Response& res) {
712-
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);
765+
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);
713766
}
714767

715768
bool setRates(SetRates::Request& req, SetRates::Response& res) {
716-
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);
769+
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);
717770
}
718771

719772
bool land(std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& res)

clover/www/index.html

+1
Original file line numberDiff line numberDiff line change
@@ -6,6 +6,7 @@ <h1>Clover Drone Kit Tools</h1>
66
<li><a href="" id="butterfly">Open web terminal</a> (<code>Butterfly</code>)</li>
77
<li><a href="viz.html">View 3D visualization</a> (<code>ros3djs</code>)</li>
88
<li><a href="aruco_map.html">3D visualization for markers map</a> (<code>ros3djs</code>)</li>
9+
<li><a href="../clover_blocks/">Blocks programming</a> (<code>Blockly</code>)</li>
910
</ul>
1011

1112
<div class="version"></div>

clover_blocks/CMakeLists.txt

+87
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,87 @@
1+
cmake_minimum_required(VERSION 2.8.3)
2+
project(clover_blocks)
3+
4+
find_package(catkin REQUIRED COMPONENTS message_generation)
5+
6+
add_message_files(
7+
FILES
8+
Prompt.msg
9+
)
10+
11+
add_service_files(
12+
FILES
13+
Run.srv
14+
Load.srv
15+
Store.srv
16+
)
17+
18+
generate_messages(
19+
DEPENDENCIES
20+
# std_msgs # Or other packages containing msgs
21+
)
22+
23+
catkin_package(
24+
# INCLUDE_DIRS include
25+
# LIBRARIES roslaunch_editor
26+
CATKIN_DEPENDS message_runtime
27+
# DEPENDS system_lib
28+
)
29+
30+
#############
31+
## Install ##
32+
#############
33+
34+
# all install targets should use catkin DESTINATION variables
35+
# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
36+
37+
## Mark executable scripts (Python etc.) for installation
38+
## in contrast to setup.py, you can choose the destination
39+
# install(PROGRAMS
40+
# scripts/my_python_script
41+
# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
42+
# )
43+
44+
## Mark executables for installation
45+
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html
46+
# install(TARGETS ${PROJECT_NAME}_node
47+
# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
48+
# )
49+
50+
## Mark libraries for installation
51+
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html
52+
# install(TARGETS ${PROJECT_NAME}
53+
# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
54+
# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
55+
# RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}
56+
# )
57+
58+
## Mark cpp header files for installation
59+
# install(DIRECTORY include/${PROJECT_NAME}/
60+
# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
61+
# FILES_MATCHING PATTERN "*.h"
62+
# PATTERN ".svn" EXCLUDE
63+
# )
64+
65+
## Mark other files for installation (e.g. launch and bag files, etc.)
66+
# install(FILES
67+
# # myfile1
68+
# # myfile2
69+
# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
70+
# )
71+
72+
catkin_install_python(PROGRAMS src/clover_blocks
73+
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
74+
)
75+
76+
#############
77+
## Testing ##
78+
#############
79+
80+
## Add gtest based cpp test target and link libraries
81+
# catkin_add_gtest(${PROJECT_NAME}-test test/test_roslaunch_editor.cpp)
82+
# if(TARGET ${PROJECT_NAME}-test)
83+
# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
84+
# endif()
85+
86+
## Add folders to be run by python nosetests
87+
# catkin_add_nosetests(test)

clover_blocks/README.md

+52
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,52 @@
1+
# clover_blocks
2+
3+
Blockly programming support for Clover.
4+
5+
<img src="screenshot.png" width=700>
6+
7+
See user documentation at the [main Clover documentation site](https://clover.coex.tech/en/blocks.html).
8+
9+
Internal package documentation is given below.
10+
11+
## Frontend
12+
13+
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.
14+
15+
## `clover_blocks` node
16+
17+
`clover_blocks` is the blocks programming backend, implementing all the services and topics needed for running Blockly-generated Python script.
18+
19+
### Services
20+
21+
* `~run` ([*clover_blocks/Run*](srv/Run.srv)) – run Blockly-generated program (in Python).
22+
* `~stop` ([*std_srvs/Trigger*](http://docs.ros.org/melodic/api/std_srvs/html/srv/Trigger.html)) – terminate the running program.
23+
* `~store` ([*clover_blocks/load*](srv/Store.srv)) – store a user program (to `<package_path>/programs` by default).
24+
* `~load` ([*clover_blocks/load*](srv/Load.srv)) – load all the stored programs.
25+
26+
### Parameters
27+
28+
* `~programs_dir` (*string*) – directory for user programs.
29+
30+
Parameters read by frontend:
31+
32+
* `~navigate_tolerance` (*float*) – distance tolerance in meters, used for navigate-like blocks (default: 0.2).
33+
* `~sleep_time` (*float*) – duration of sleep in loop cycles, used for navigate-like blocks (default: 0.2).
34+
35+
These parameters also can be set as URL GET-parameters, for example:
36+
37+
```
38+
http://<hostname>/clover_blocks/?navigate_tolerance=0.5&sleep_time=0.1
39+
```
40+
41+
### Topics
42+
43+
#### Published
44+
45+
* `~running` ([*std_msgs/Bool*](http://docs.ros.org/melodic/api/std_msgs/html/msg/Bool.html)) – indicates if the program is currently running.
46+
* `~block` ([*std_msgs/String*](http://docs.ros.org/melodic/api/std_msgs/html/msg/String.html)) – current executing block (maximum topic rate is limited).
47+
* `~error` ([*std_msgs/String*](http://docs.ros.org/melodic/api/std_msgs/html/msg/String.html)) – user program errors and exceptions.
48+
* `~prompt` ([*clover_blocks/Prompt*](msg/Prompt.msg)) – user input request (includes random request ID string).
49+
50+
This topic is published from the frontend side:
51+
52+
* `~prompt/<request_id>` ([*std_msgs/String*](http://docs.ros.org/melodic/api/std_msgs/html/msg/String.html)) – user input response.

clover_blocks/msg/Prompt.msg

+2
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,2 @@
1+
string message # message for prompt
2+
string id # user response should be published to ~input/<id> topic

0 commit comments

Comments
 (0)