Skip to content

Commit

Permalink
Merge branch 'master' of ssh://bitbucket.pheno.robopec.com:7998/phen/…
Browse files Browse the repository at this point in the history
…rosserial_qt
  • Loading branch information
1r0b1n0 committed Jan 12, 2018
2 parents aae474a + 052525e commit 27ff39e
Show file tree
Hide file tree
Showing 20 changed files with 411 additions and 363 deletions.
2 changes: 2 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
@@ -1 +1,3 @@
CMakeLists.txt.user*
/ros_lib

8 changes: 8 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -7,4 +7,12 @@ find_package(catkin REQUIRED COMPONENTS roscpp rosserial_msgs rosserial_python r

catkin_package()

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

catkin_install_python(
PROGRAMS scripts/make_library.py
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
)
19 changes: 13 additions & 6 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,33 +1,40 @@
# 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.
For the moment it only supports TCP/IP, but it could be easily adapted for 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
* C++11 support is required
* Unlike other client implementations 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, using the Qt event loop
* 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
To use the examples you should first generate the *ros_lib* directory, for example like this :
```
roscd rosserial_qt
rosrun rosserial_qt make_library.py .
```

## Performance
CPU usage is quite close to native roscpp nodes :
CPU usage seems to be quite close to native roscpp nodes.
(TODO : add some data)

## Supported platforms
This library should work on all platforms supported by Qt (Linux, Windows, macos, ios, android ...)
This library should work on all platforms supported by Qt (Linux, Windows, Android, ios...)
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.
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 (modified version available here : [https://github.com/1r0b1n0/rosserial](https://github.com/1r0b1n0/rosserial) ), 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.

Expand Down
2 changes: 2 additions & 0 deletions launch/rosserial_python_server.launch
Original file line number Diff line number Diff line change
@@ -1,4 +1,6 @@
<launch>
<!-- Do not use ; does not yet work with 32bit messages -->

<node pkg="rosserial_python" type="serial_node.py" name="serial_node" output="screen">
<param name="port" value="tcp"/>
</node>
Expand Down
22 changes: 20 additions & 2 deletions src/ros_lib/node_handle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@

#ifdef ERROR
// ach, windows.h polluting everything again,
// clashes with autogenerated rosgraph_msgs/Log.h
// clashes with autogenerated rosgraph_msgs/Log.h
#undef ERROR
#endif
#include "rosserial_msgs/Log.h"
Expand Down Expand Up @@ -46,7 +46,8 @@ ros::NodeHandle::NodeHandle(uint32_t input_size, uint32_t output_size, QObject *
INPUT_SIZE(input_size),
OUTPUT_SIZE(output_size),
configured_(false),
isActive_(false)
isActive_(false),
latency_(NAN)
{
message_in.resize(INPUT_SIZE);
message_out.resize(OUTPUT_SIZE);
Expand Down Expand Up @@ -233,6 +234,8 @@ void ros::NodeHandle::requestSyncTime()

void ros::NodeHandle::syncTime(uint8_t *data)
{
uint32_t latency_ms = hardware_.time() - rt_time;

std_msgs::Time t;
uint32_t offset = hardware_.time() - rt_time;

Expand All @@ -242,6 +245,10 @@ void ros::NodeHandle::syncTime(uint8_t *data)

this->setNow(t.data);
last_sync_receive_time = hardware_.time();

// update latency property
latency_ = latency_ms/1000.;
emit latencyChanged(latency_);
}

ros::Time ros::NodeHandle::now()
Expand Down Expand Up @@ -427,11 +434,22 @@ bool ros::NodeHandle::getParam(const std::string &name, std::string *param, unsi
return false;
}

float NodeHandle::latency() const
{
return latency_;
}

void NodeHandle::setConfigured(bool isConnected)
{
if (configured_ == isConnected)
return;

configured_ = isConnected;
emit isConnectedChanged(configured_);

if(!isConnected)
{
latency_ = NAN;
emit latencyChanged(latency_);
}
}
6 changes: 3 additions & 3 deletions src/ros_lib/ros/RosQtSocket.h
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
/**
Software License Agreement (BSD)
\file WindowsSocket.h
\authors Kareem Shehata <kshehata@clearpathrobotics.com>
\copyright Copyright (c) 2014, Clearpath Robotics, Inc., All rights reserved.
\file RosQtSocket.h
\authors Robin Vanhove <r.vanhove@robopec.com>
\copyright Copyright (c) 2017, Robopec, All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that
the following conditions are met:
Expand Down
190 changes: 190 additions & 0 deletions src/ros_lib/ros/action_client.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,190 @@
/*
* Software License Agreement (BSD License)
*
* Copyright (c) 2017, Robopec
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of Willow Garage, Inc. nor the names of its
* contributors may be used to endorse or promote prducts derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/

#ifndef ROS_ACTION_CLIENT_H_
#define ROS_ACTION_CLIENT_H_

#include <functional>
#include <string>
#include "rosserial_msgs/TopicInfo.h"

#include "ros/publisher.h"
#include "ros/subscriber.h"
#include "../actionlib_msgs/GoalID.h"
#include "../actionlib_msgs/GoalStatusArray.h"

namespace ros {

#define ACTION_DEFINITION(ActionSpec) \
typedef typename ActionSpec::_action_goal_type ActionGoal; \
typedef typename ActionGoal::_goal_type Goal; \
typedef typename ActionSpec::_action_result_type ActionResult; \
typedef typename ActionResult::_result_type Result; \
typedef typename ActionSpec::_action_feedback_type ActionFeedback; \
typedef typename ActionFeedback::_feedback_type Feedback;

template<typename ActionType>
class ActionClient {
ACTION_DEFINITION(ActionType)
public:
typedef std::function<void(const Feedback&)> FeedbackCallbackT;
typedef std::function<void(const Result&)> ResultCallbackT;
typedef std::function<void(uint8_t)> StateChangedCallbackT;

enum StateEnum
{
PENDING,
ACTIVE,
PREEMPTED,
SUCCEEDED,
ABORTED,
REJECTED,
PREEMPTING,
RECALLING,
RECALLED,
LOST,
INACTIVE
};

ActionClient(const std::string& action_name) :
goal_pub(action_name + "/goal"),
cancel_pub(action_name + "/cancel"),
status_sub(action_name + "/status", std::bind(&ActionClient::status_cb_internal, this, std::placeholders::_1)),
feedback_sub(action_name + "/feedback", std::bind(&ActionClient::feedback_cb_internal, this, std::placeholders::_1)),
result_sub(action_name + "/result", std::bind(&ActionClient::result_cb_internal, this, std::placeholders::_1))
{
resetState();
}

void sendGoal(const Goal& goal, FeedbackCallbackT feedback_cb = FeedbackCallbackT(), ResultCallbackT result_cb = ResultCallbackT())
{
if(!goal_pub.nh_->connected()) return;

feedback_cb_ = feedback_cb;
result_cb_ = result_cb;

ActionGoal action_goal_msg;
// no goal id and stamp -> will be generated by the action server
// see: http://wiki.ros.org/actionlib/DetailedDescription
action_goal_msg.goal = goal;
goal_pub.publish(action_goal_msg);
}

void cancelGoal()
{
actionlib_msgs::GoalID msg;
// no goal id and stamp -> cancel all goals
// see: http://wiki.ros.org/actionlib/DetailedDescription
cancel_pub.publish(msg);
}

void registerStateCallback(StateChangedCallbackT state_cb)
{
state_cb_ = state_cb;
resetState();
}

void unregisterStateCallback()
{
state_cb_ = StateChangedCallbackT();
}

uint8_t getState() const
{
return status_.status;
}

std::string getStateText() const
{
return status_.text;
}

private:
void status_cb_internal(const actionlib_msgs::GoalStatusArray& msg)
{
if(!msg.status_list.empty())
{
if(state_cb_ && (msg.status_list.back().status != status_.status))
{
state_cb_(msg.status_list.back().status);
}

status_ = msg.status_list.back();
}
else
{
resetState();
}
}

void feedback_cb_internal(const ActionFeedback& msg)
{
if(feedback_cb_)
{
feedback_cb_(msg.feedback);
}
}

void result_cb_internal(const ActionResult& msg)
{
if(result_cb_)
{
result_cb_(msg.result);
}
}

void resetState()
{
status_.goal_id = actionlib_msgs::GoalID();
status_.text = "inactive";
status_.status = INACTIVE;
}

FeedbackCallbackT feedback_cb_;
ResultCallbackT result_cb_;
StateChangedCallbackT state_cb_;
size_t goal_count_= 0;
actionlib_msgs::GoalStatus status_;

public:
Publisher<ActionGoal> goal_pub;
Publisher<actionlib_msgs::GoalID> cancel_pub;
Subscriber<actionlib_msgs::GoalStatusArray> status_sub;
Subscriber<ActionFeedback> feedback_sub;
Subscriber<ActionResult> result_sub;
};

}

#endif // ROS_ACTION_CLIENT_H_
Loading

0 comments on commit 27ff39e

Please sign in to comment.