Skip to content

Commit

Permalink
dev
Browse files Browse the repository at this point in the history
  • Loading branch information
1r0b1n0 committed Oct 13, 2017
1 parent fe892ba commit 2ef03f4
Show file tree
Hide file tree
Showing 21 changed files with 934 additions and 264 deletions.
1 change: 1 addition & 0 deletions .gitignore
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
CMakeLists.txt.user*
117 changes: 4 additions & 113 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,119 +1,10 @@
cmake_minimum_required(VERSION 2.8.3)
cmake_minimum_required(VERSION 2.8.11)
project(rosserial_qt)

## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(catkin REQUIRED COMPONENTS
roscpp
rospy
std_msgs
)
add_definitions(-std=c++11)

## System dependencies are found with CMake's conventions
# find_package(Boost REQUIRED COMPONENTS system)
find_package(catkin REQUIRED COMPONENTS roscpp rosserial_msgs rosserial_python rosserial_server rostest std_msgs)

catkin_package()

## Uncomment this if the package has a setup.py. This macro ensures
## modules and global scripts declared therein get installed
## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
# catkin_python_setup()

###################################
## catkin specific configuration ##
###################################
## The catkin_package macro generates cmake config files for your package
## Declare things to be passed to dependent projects
## INCLUDE_DIRS: uncomment this if you package contains header files
## LIBRARIES: libraries you create in this project that dependent projects also need
## CATKIN_DEPENDS: catkin_packages dependent projects also need
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
# INCLUDE_DIRS include
# LIBRARIES rosserial_qt
# CATKIN_DEPENDS message_runtime
# DEPENDS system_lib
)

###########
## Build ##
###########

## Specify additional locations of header files
## Your package locations should be listed before other locations
# include_directories(include)

## Declare a C++ library
# add_library(rosserial_qt
# src/${PROJECT_NAME}/rosserial_qt.cpp
# )

## Add cmake target dependencies of the library
## as an example, code may need to be generated before libraries
## either from message generation or dynamic reconfigure
# add_dependencies(rosserial_qt ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})

## Declare a C++ executable
# add_executable(rosserial_qt_node src/rosserial_qt_node.cpp)

## Add cmake target dependencies of the executable
## same as for the library above
# add_dependencies(rosserial_qt_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})

## Specify libraries to link a library or executable target against
# target_link_libraries(rosserial_qt_node
# ${catkin_LIBRARIES}
# )

#############
## 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/make_library.py
# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )

## Mark executables and/or libraries for installation
# install(TARGETS rosserial_qt rosserial_qt_node
# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# RUNTIME DESTINATION ${CATKIN_PACKAGE_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}
# )

# install(DIRECTORY
# src/ros_lib
# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/src
# )

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

## Add gtest based cpp test target and link libraries
# catkin_add_gtest(${PROJECT_NAME}-test test/test_rosserial_qt.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)
44 changes: 44 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,44 @@
# rosserial_qt

Client implementation for rosserial using the multi-platform Qt library.
For the moment it only supports TCP/IP, but it should be easily adapted to UDP (using QUdpSocket) or serial port (using QSerialPort) communications.

## Usage

1. Generate the source files by running `rosrun rosserial_qt make_library.py <output_path>`
2. Compile your client application using the library. You should add the roslib library to you include path, and add the .cpp files to your source files.

Remarks:
* Unlike other clients of rosserial, the *NodeHandle* uses a dynamically sized buffer.
* There is no need to call spinOnce() manually : the *NodeHandle* will call spinOnce() periodically and on reception of new data
* Unlike rosserial_arduino using C-style arrays, the message generation script will convert arrays to std::vector and std::array

## Examples
Some simple examples of applications using the library are in the *test* directory

## Performance
CPU usage is quite close to native roscpp nodes :

## Supported platforms
This library should work on all platforms supported by Qt (Linux, Windows, macos, ios, android ...)
I have succesfully tested this library on :
* Linux
* Windows

## Server-side configuration

The current implementation needs the message length to be coded on 4 bytes (rosserial's default is 2 bytes). This has been implemented in rosserial-server, but has to be configured with the *msg_length_bytes* parameter.
You should also configure the receive buffer size depending of your application.
The rosserial-python server implementation will not work, as it doesn't support 4 bytes coding of the message length.

Example launch file :
```
<launch>
<node pkg="rosserial_server" type="socket_node" name="rosserial_server_socket_node">
<param name="msg_length_bytes" value="4"/>
<param name="buffer_size" value="1000000"/>
<param name="tcp_nodelay" value="true"/>
</node>
<node pkg="rosserial_python" type="message_info_service.py" name="rosserial_message_info" />
</launch>
```
1 change: 1 addition & 0 deletions launch/server.launch
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@
<node pkg="rosserial_server" type="socket_node" name="rosserial_server_socket_node">
<param name="msg_length_bytes" value="4"/>
<param name="buffer_size" value="1000000"/>
<param name="tcp_nodelay" value="true"/>
</node>
<node pkg="rosserial_python" type="message_info_service.py" name="rosserial_message_info" />
</launch>
8 changes: 5 additions & 3 deletions scripts/make_library.py
Original file line number Diff line number Diff line change
Expand Up @@ -495,14 +495,15 @@ def _write_std_includes(self, f):
f.write('#include <stdint.h>\n')
f.write('#include <string.h>\n')
f.write('#include <stdlib.h>\n')
f.write('#include <string>\n')
f.write('#include <vector>\n')
f.write('#include <array>\n')
f.write('#include <stdexcept>\n')
f.write('#include <QJsonParseError>\n')
f.write('#include <QJsonDocument>\n')
f.write('#include <QJsonObject>\n')
f.write('#include <QJsonArray>\n')
f.write('#include "ros/msg.h"\n')
f.write('#include <ros/msg.h>\n')

def _write_msg_includes(self, f):
for i in self.includes:
Expand Down Expand Up @@ -760,7 +761,7 @@ def rosserial_client_copy_files(rospack, path):
'int32': ('int32_t', 4, PrimitiveDataType, []),
'uint32': ('uint32_t', 4, PrimitiveDataType, []),
'int64': ('int64_t', 8, PrimitiveDataType, []),
'uint64': ('uint64_t', 4, PrimitiveDataType, []),
'uint64': ('uint64_t', 8, PrimitiveDataType, []),
'float32': ('float', 4, PrimitiveDataType, []),
'float64': ('double', 8, PrimitiveDataType, []),
'time': ('ros::Time', 8, TimeDataType, ['ros/time']),
Expand Down Expand Up @@ -794,7 +795,8 @@ def main():

# copy ros_lib stuff in
src_dir = rospack.get_path("rosserial_qt")
#shutil.copytree(src_dir + "/src/ros_lib", path + "/ros_lib")
shutil.rmtree(path + "/ros_lib", ignore_errors = True)
shutil.copytree(src_dir + "/src/ros_lib", path + "/ros_lib")

rosserial_generate(rospack, path + "/ros_lib")

Expand Down
40 changes: 25 additions & 15 deletions src/ros_lib/ros/node_handle.h
Original file line number Diff line number Diff line change
Expand Up @@ -91,7 +91,10 @@ const uint8_t MODE_MESSAGE = 9;
const uint8_t MODE_MSG_CHECKSUM = 10; // checksum for msg and topic id

const uint32_t SERIAL_MSG_TIMEOUT = 2000; // 2000 milliseconds to recieve all of message data
const uint32_t READ_BUFFER_SIZE = 4096;
const uint32_t READ_BUFFER_SIZE = 4096; // at each read() we will ask up to READ_BUFFER_SIZE bytes

const size_t MESSAGE_HEADER_BYTES = 10; // size of the header
const size_t BUFFER_OVER_ALLOCATION = 100*1024; //if the tx or rx buffer hasn't enough capacity, we will allocate this more

using rosserial_msgs::TopicInfo;

Expand Down Expand Up @@ -121,7 +124,7 @@ class NodeHandle : public NodeHandleBase_
* Setup Functions
*/
public:
NodeHandle(uint32_t input_size=10000000, uint32_t output_size=10000000, QObject *parent=0) :
NodeHandle(uint32_t input_size=10000, uint32_t output_size=10000, QObject *parent=0) :
NodeHandleBase_(parent),
INPUT_SIZE(input_size),
OUTPUT_SIZE(output_size),
Expand Down Expand Up @@ -272,6 +275,13 @@ class NodeHandle : public NodeHandleBase_
}else if( mode_ == MODE_TOPIC_H ){ /* top half of topic id */
topic_ += data<<8;
mode_ = MODE_MESSAGE;

// if needed expand buffer
if(bytes_ + MESSAGE_HEADER_BYTES > message_in.size())
{
message_in.resize(bytes_ + MESSAGE_HEADER_BYTES + BUFFER_OVER_ALLOCATION);
}

if(bytes_ == 0)
mode_ = MODE_MSG_CHECKSUM;
}else if( mode_ == MODE_MSG_CHECKSUM ){ /* do checksum */
Expand Down Expand Up @@ -381,8 +391,8 @@ class NodeHandle : public NodeHandleBase_
}

/* Register a new Service Server */
template<typename MReq, typename MRes, typename ObjT>
bool advertiseService(ServiceServer<MReq,MRes,ObjT>& srv){
template<typename MType>
bool advertiseService(ServiceServer<MType>& srv){
bool v = advertise(srv.pub);
size_t i = subscribers.size();
subscribers.push_back(static_cast<Subscriber_*>(&srv));
Expand Down Expand Up @@ -438,13 +448,19 @@ class NodeHandle : public NodeHandleBase_

/* serialize message */
size_t expected_l = msg->serialize_size();
if( expected_l+9 >= OUTPUT_SIZE ){
logerror("Message from device dropped: message larger than buffer.");
return -1;

if(expected_l + MESSAGE_HEADER_BYTES > message_out.size())
{
message_out.resize(expected_l + MESSAGE_HEADER_BYTES + BUFFER_OVER_ALLOCATION);
}

size_t l = msg->serialize(message_out.data()+9);

if(expected_l != l)
{
logerror("Internal error : expected_l != l ; memory could be corrupted");
}

/* setup the header */
message_out[0] = 0xff;
message_out[1] = PROTOCOL_VER;
Expand All @@ -463,19 +479,13 @@ class NodeHandle : public NodeHandleBase_
chk += message_out[i];
message_out[l++] = 255 - (chk%256);

if( l <= OUTPUT_SIZE ){
hardware_.write(message_out.data(), l);
return l;
}else{
logerror("Message from device dropped: message larger than buffer.");
return -1;
}
hardware_.write(message_out.data(), l);
return l;
}

private slots:
void onReadyRead()
{
std::cout << "ready read" << std::endl;
spinOnce();
}

Expand Down
12 changes: 6 additions & 6 deletions src/ros_lib/ros/service_client.h
Original file line number Diff line number Diff line change
Expand Up @@ -46,19 +46,19 @@ namespace ros {
template<typename MType>
class ServiceClient : public Subscriber_ {

typedef typename MType::Request MReq;
typedef typename MType::Response MRes;
typedef std::function<void(const MRes&)> CallBackT;

public:
typedef typename MType::Request MReq;
typedef typename MType::Response MRes;
typedef std::function<void(const MRes&)> CallbackT;

ServiceClient(const char* topic_name) :
pub(topic_name, rosserial_msgs::TopicInfo::ID_SERVICE_CLIENT + rosserial_msgs::TopicInfo::ID_PUBLISHER)
{
this->topic_ = topic_name;
this->waiting = false;
}

void call(const MReq & request, CallBackT callback)
void call(const MReq & request, CallbackT callback)
{
if(waiting)
{
Expand Down Expand Up @@ -88,7 +88,7 @@ namespace ros {
}

bool waiting;
CallBackT cb_;
CallbackT cb_;

public:
Publisher<MReq> pub;
Expand Down
Loading

0 comments on commit 2ef03f4

Please sign in to comment.