Skip to content

Commit c9d48c2

Browse files
Merge pull request #4 from DrawZeroPoint/dzp-dev
Dzp dev
2 parents 1f4e804 + ff204ce commit c9d48c2

File tree

77 files changed

+5145
-3024
lines changed

Some content is hidden

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

77 files changed

+5145
-3024
lines changed

CMakeLists.txt

Lines changed: 46 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -69,6 +69,8 @@ endif ()
6969
find_library(CARTESIO_LIB CartesianInterface HINTS /opt/xbot/)
7070
if (CARTESIO_LIB)
7171
message(STATUS "Found CARTESIO_LIB ${CARTESIO_LIB}")
72+
find_package(OpenSoT REQUIRED)
73+
find_package(cartesian_interface REQUIRED)
7274
else ()
7375
message(WARNING "CARTESIO_LIB not found")
7476
endif ()
@@ -97,6 +99,7 @@ add_service_files(
9799
FILES
98100
ExecuteAddCollisionBox.srv
99101
ExecuteAddCollisionPlane.srv
102+
ExecuteAllLockedPoses.srv
100103
ExecuteAllPlans.srv
101104
ExecuteAllPoses.srv
102105
ExecuteAttachCollisionBox.srv
@@ -166,8 +169,8 @@ generate_messages(
166169
# )
167170

168171
catkin_package(
169-
# INCLUDE_DIRS include
170-
LIBRARIES
172+
INCLUDE_DIRS include
173+
LIBRARIES ${PROJECT_NAME}
171174
CATKIN_DEPENDS ${ROS_DEPENDENCIES}
172175
)
173176

@@ -223,14 +226,17 @@ if (HPP_CORE_LIB AND HPP_FCL_LIB)
223226
endif ()
224227

225228
if (CARTESIO_LIB)
226-
include_directories(/opt/xbot/include)
227-
add_library(${PROJECT_NAME}_CARTESIO_ADDON
228-
src/lib/cartesio_server.cpp
229-
)
230-
target_link_libraries(${PROJECT_NAME}_CARTESIO_ADDON
229+
include_directories(/opt/xbot/include ${OpenSoT_INCLUDE_DIRS})
230+
add_library(${PROJECT_NAME}_cartesio src/lib/cartesio_server.cpp)
231+
target_link_libraries(${PROJECT_NAME}_cartesio ${catkin_LIBRARIES})
232+
add_dependencies(${PROJECT_NAME}_cartesio ${PROJECT_NAME}_generate_messages_cpp)
233+
234+
add_library(${PROJECT_NAME}_cartesio_addon src/lib/cartesio_addon.cpp)
235+
add_dependencies(${PROJECT_NAME}_cartesio_addon ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
236+
target_link_libraries(${PROJECT_NAME}_cartesio_addon
231237
${catkin_LIBRARIES}
232-
)
233-
add_dependencies(${PROJECT_NAME}_CARTESIO_ADDON ${PROJECT_NAME}_generate_messages_cpp)
238+
${OpenSoT_LIBRARIES}
239+
${cartesian_interface_LIBRARIES})
234240
endif ()
235241

236242
#####################
@@ -288,7 +294,7 @@ if (CARTESIO_LIB)
288294
target_link_libraries(roport_cartesio_server
289295
${catkin_LIBRARIES}
290296
${PROJECT_NAME}
291-
${PROJECT_NAME}_CARTESIO_ADDON
297+
${PROJECT_NAME}_cartesio
292298
)
293299
endif ()
294300

@@ -301,12 +307,42 @@ catkin_install_python(PROGRAMS
301307
${PY_SOURCES}
302308
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION})
303309

310+
# Mark executables for installation
311+
install(TARGETS
312+
roport_task_scheduler
313+
roport_robot_interface
314+
roport_moveit_cpp_server
315+
roport_msg_converter
316+
roport_msg_aggregator
317+
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
318+
)
319+
320+
if (CARTESIO_LIB)
321+
install(TARGETS roport_cartesio_server
322+
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
323+
)
324+
endif ()
325+
304326
install(DIRECTORY
305327
launch
306328
tree
307329
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
308330
)
309331

332+
# Mark cpp header files for installation
333+
install(DIRECTORY include/${PROJECT_NAME}/
334+
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
335+
FILES_MATCHING PATTERN "common.h"
336+
PATTERN ".svn" EXCLUDE
337+
)
338+
339+
# Mark libraries for installation
340+
install(TARGETS ${PROJECT_NAME}
341+
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
342+
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
343+
RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}
344+
)
345+
310346
#############
311347
## Testing ##
312348
#############

README.md

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,10 @@
22

33
<img alt="logo" height="120" src="misc/image/ms-icon-310x310.png" width="120"/>
44

5-
[![CI](https://github.com/DrawZeroPoint/RoTools/actions/workflows/ci.yml/badge.svg?branch=master)](https://github.com/DrawZeroPoint/RoTools/actions/workflows/ci.yml)
5+
<p align="left">
6+
<a href="https://github.com/DrawZeroPoint/RoTools/actions/workflows/ci.yml"><img alt="CI" src="https://github.com/DrawZeroPoint/RoTools/actions/workflows/ci.yml/badge.svg?branch=master"></a>
7+
<a href="https://github.com/psf/black"><img alt="Code style: black" src="https://img.shields.io/badge/code%20style-black-000000.svg"></a>
8+
</p>
69

710
RoTools is an all-in-one ROS package for high-level robotic task scheduling, visual perception, path planning,
811
simulation, and direct-/tele-manipulation control. It leverages BehaviorTree to deliver fast task construction and

include/roport/cartesio_server.h

Lines changed: 35 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -43,6 +43,7 @@
4343
#include <cartesian_interface/ReachPoseAction.h>
4444
#include <trajectory_msgs/JointTrajectory.h>
4545

46+
#include <roport/ExecuteAllLockedPoses.h>
4647
#include <roport/ExecuteAllPoses.h>
4748
#include <roport/ExecuteMirroredPose.h>
4849

@@ -64,16 +65,29 @@ class CartesIOServer {
6465
tf2_ros::TransformListener tf_listener_;
6566

6667
ros::ServiceServer execute_all_poses_srv_;
67-
ros::ServiceServer execute_mirrored_pose_srv_;
68+
ros::ServiceServer execute_all_locked_poses_srv_;
6869

6970
using reachPoseActionClient = actionlib::SimpleActionClient<cartesian_interface::ReachPoseAction>;
7071
std::vector<std::shared_ptr<reachPoseActionClient>> control_clients_;
7172

73+
/**
74+
* Move the groups to corresponding poses.
75+
* @param req
76+
* @param resp
77+
* @return
78+
*/
7279
auto executeAllPosesSrvCb(roport::ExecuteAllPoses::Request& req, roport::ExecuteAllPoses::Response& resp) -> bool;
73-
// auto executeMirroredPoseSrvCb(roport::ExecuteMirroredPose::Request& req, roport::ExecuteMirroredPose::Response&
74-
// resp)
75-
// -> bool;
76-
//
80+
81+
/**
82+
* Move the groups to corresponding poses. If only one group is given, this is identical with executeAllPosesSrvCb,
83+
* if multiple groups are given, the first group's pose will be the target, while other groups will move along with
84+
* the first and keep their relative poses unchanged during the movement.
85+
* @param req
86+
* @param resp
87+
* @return
88+
*/
89+
auto executeAllLockedPosesSrvCb(roport::ExecuteAllLockedPoses::Request& req,
90+
roport::ExecuteAllLockedPoses::Response& resp) -> bool;
7791

7892
void buildActionGoal(const int& index,
7993
const geometry_msgs::Pose& goal_pose,
@@ -84,12 +98,23 @@ class CartesIOServer {
8498
auto executeGoals(const std::map<int, cartesian_interface::ReachPoseActionGoal>& goals, double duration = 120)
8599
-> bool;
86100

87-
// static void getMirroredTrajectory(MoveGroupInterface& move_group,
88-
// trajectory_msgs::JointTrajectory trajectory,
89-
// std::vector<double> mirror_vector,
90-
// trajectory_msgs::JointTrajectory& mirrored_trajectory);
91-
92101
bool getTransform(const int& index, geometry_msgs::TransformStamped& transform);
102+
103+
/**
104+
* Given the index of the group in group_names_, get current pose of that group's control frame wrt the reference
105+
* frame.
106+
* @param index Group index in group_names_.
107+
* @param pose Pose of the control frame.
108+
* @return True if succeed, false otherwise.
109+
*/
110+
bool getCurrentPoseWithIndex(const int& index, geometry_msgs::Pose& pose);
111+
112+
void getGoalPoseWithReference(const int& ref_idx,
113+
const geometry_msgs::Pose& curr_ref_pose,
114+
const geometry_msgs::Pose& goal_ref_pose,
115+
const int& idx,
116+
const geometry_msgs::Pose& curr_pose,
117+
geometry_msgs::Pose& goal_pose);
93118
};
94119

95120
} // namespace roport

include/roport/common.h

Lines changed: 80 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -53,6 +53,14 @@ inline auto getParam(const ros::NodeHandle& node_handle,
5353
return true;
5454
}
5555

56+
inline auto getIndex(const std::vector<std::string>& names, const std::string& target) -> int {
57+
auto res = std::find(names.begin(), names.end(), target);
58+
if (res != names.end()) {
59+
return res - names.begin();
60+
}
61+
return -1;
62+
}
63+
5664
inline void geometryPoseToEigenMatrix(const geometry_msgs::Pose& pose, Eigen::Matrix4d& mat) {
5765
mat = Eigen::Matrix4d::Identity();
5866

@@ -136,6 +144,24 @@ inline void localAlignedPoseToGlobalPose(const geometry_msgs::Pose& pose_local_a
136144
eigenMatrixToGeometryPose(mat_global_to_target, pose_global_to_target);
137145
}
138146

147+
inline void toGlobalPose(const int& goal_type,
148+
const geometry_msgs::Pose& current_pose,
149+
const geometry_msgs::Pose& cmd_pose,
150+
geometry_msgs::Pose& goal_pose) {
151+
if (goal_type == 0) {
152+
// The given pose is already in the reference frame
153+
goal_pose = cmd_pose;
154+
} else if (goal_type == 1) {
155+
// The given pose is relative to the local aligned frame having the same orientation as the reference frame
156+
localAlignedPoseToGlobalPose(cmd_pose, current_pose, goal_pose, true);
157+
} else if (goal_type == 2) {
158+
// The given pose is relative to the local frame
159+
localPoseToGlobalPose(cmd_pose, current_pose, goal_pose);
160+
} else {
161+
throw std::invalid_argument("Goal type not supported");
162+
}
163+
}
164+
139165
inline auto isPoseLegal(const geometry_msgs::Pose& pose) -> bool {
140166
if (pose.orientation.w == 0 && pose.orientation.x == 0 && pose.orientation.y == 0 && pose.orientation.z == 0) {
141167
ROS_ERROR("The pose is empty (all orientation coefficients are zero)");
@@ -149,6 +175,60 @@ inline auto isPoseLegal(const geometry_msgs::Pose& pose) -> bool {
149175
return true;
150176
}
151177

178+
/**
179+
* Converting a quaternion representing a planar rotation to theta.
180+
* @param quat Quaternion msg.
181+
* @return theta.
182+
*/
183+
inline double quaternionToTheta(const geometry_msgs::Quaternion& quat) {
184+
Eigen::Quaterniond quaternion(quat.w, quat.x, quat.y, quat.z);
185+
Eigen::Rotation2Dd rot(quaternion.toRotationMatrix().topLeftCorner<2, 2>());
186+
return rot.smallestPositiveAngle();
187+
}
188+
189+
/**
190+
* Pretty print a Eigen matrix. Its size, row number, and column number will also be displayed.
191+
* @param mat A matrix with various shape to print.
192+
* @param precision How many digits to keep after the decimal point.
193+
*/
194+
inline void prettyPrintEigenMatrix(const Eigen::Matrix<double, Eigen::Dynamic, Eigen::Dynamic>& mat,
195+
const int& precision = 3) {
196+
Eigen::IOFormat cleanFormat(precision, 0, ", ", "\n", "[", "]");
197+
std::cout << "Matrix size: " << mat.size() << " rows: " << mat.rows() << " cols: " << mat.cols() << std::endl;
198+
std::cout << mat.format(cleanFormat) << std::endl;
199+
}
200+
201+
inline void getCartesianError(const Eigen::Vector3d& current_position,
202+
const Eigen::Quaterniond& current_orientation,
203+
const Eigen::Vector3d& goal_position,
204+
const Eigen::Quaterniond& goal_orientation,
205+
Eigen::Matrix<double, 6, 1>& error) {
206+
error.head(3) << current_position - goal_position;
207+
208+
Eigen::Affine3d current_affine_transform;
209+
current_affine_transform.translation() = current_position;
210+
current_affine_transform.linear() = current_orientation.toRotationMatrix();
211+
212+
Eigen::Quaterniond regularized_current_orientation;
213+
regularized_current_orientation.coeffs() << current_orientation.coeffs();
214+
if (goal_orientation.coeffs().dot(current_orientation.coeffs()) < 0.) {
215+
regularized_current_orientation.coeffs() << -current_orientation.coeffs();
216+
}
217+
Eigen::Quaterniond error_quaternion(regularized_current_orientation.inverse() * goal_orientation);
218+
error.tail(3) << error_quaternion.x(), error_quaternion.y(), error_quaternion.z();
219+
error.tail(3) << -current_affine_transform.linear() * error.tail(3);
220+
}
221+
222+
inline void getCartesianError(const Eigen::Affine3d& current_transform,
223+
const Eigen::Affine3d& goal_transform,
224+
Eigen::Matrix<double, 6, 1>& error) {
225+
Eigen::Vector3d current_position(current_transform.translation());
226+
Eigen::Quaterniond current_orientation(current_transform.linear());
227+
Eigen::Vector3d goal_position(goal_transform.translation());
228+
Eigen::Quaterniond goal_orientation(goal_transform.linear());
229+
getCartesianError(current_position, current_orientation, goal_position, goal_orientation, error);
230+
}
231+
152232
/**
153233
* Judge if all corresponding elements in the two given vectors are close to each other under the tolerance.
154234
* @tparam T Value type.

scripts/roport_flask_server_template.py

Lines changed: 18 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -17,11 +17,11 @@
1717
# Custom functions
1818
# TODO add this
1919

20-
'''
20+
"""
2121
Note that this is a template for guiding the usage of Flask server
2222
for porting the algorithm using Python3. You could implement the
2323
server for your algorithm by referring this.
24-
'''
24+
"""
2525

2626
app = Flask(__name__, template_folder="templates")
2727

@@ -49,14 +49,18 @@ def decode_b64_to_image(b64_str, is_bgr=True):
4949
img = base64.b64decode(b64_str)
5050
# imdecode use the same flag as imread. cf. https://docs.opencv.org/3.4/d8/d6a/group__imgcodecs__flags.html
5151
if is_bgr:
52-
return True, cv2.imdecode(np.frombuffer(img, dtype=np.uint8), cv2.IMREAD_COLOR)
52+
return True, cv2.imdecode(
53+
np.frombuffer(img, dtype=np.uint8), cv2.IMREAD_COLOR
54+
)
5355
else:
54-
return True, cv2.imdecode(np.frombuffer(img, dtype=np.uint8), cv2.IMREAD_ANYDEPTH)
56+
return True, cv2.imdecode(
57+
np.frombuffer(img, dtype=np.uint8), cv2.IMREAD_ANYDEPTH
58+
)
5559
except cv2.error:
5660
return False, None
5761

5862

59-
@app.route('/process', methods=['POST'])
63+
@app.route("/process", methods=["POST"])
6064
def process():
6165
"""The main entrance of the server.
6266
@@ -65,34 +69,34 @@ def process():
6569
"""
6670
try:
6771
req_data = json.loads(request.data)
68-
if 'body' not in req_data:
72+
if "body" not in req_data:
6973
return make_response("Failed to load request data", 200)
7074
else:
71-
req_body = req_data['body']
75+
req_body = req_data["body"]
7276
except ValueError:
7377
return make_response("Failed to phase JSON", 200)
7478

7579
header = {}
76-
response = {'status': False, 'results': []}
80+
response = {"status": False, "results": []}
7781

7882
cv_image_list = []
79-
image_strings = json.loads(req_body['images'])
83+
image_strings = json.loads(req_body["images"])
8084
for s in image_strings:
8185
ok, image = decode_b64_to_image(s)
8286
if not ok:
83-
feedback = {'header': header, 'response': response}
87+
feedback = {"header": header, "response": response}
8488
return make_response(json.dumps(feedback), 200)
8589
cv_image_list.append(image)
8690

8791
ok, results = get_results(cv_image_list)
8892
torch.cuda.empty_cache()
8993

9094
if ok:
91-
response['status'] = True
92-
response['results'] = json.dumps(results)
93-
feedback = {'header': header, 'response': response}
95+
response["status"] = True
96+
response["results"] = json.dumps(results)
97+
feedback = {"header": header, "response": response}
9498
return make_response(json.dumps(feedback), 200)
9599

96100

97101
if __name__ == "__main__":
98-
waitress.serve(app, host='0.0.0.0', port=6060, threads=6)
102+
waitress.serve(app, host="0.0.0.0", port=6060, threads=6)

0 commit comments

Comments
 (0)