Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add ROS driver package for QCR force sensor #473

Draft
wants to merge 1 commit into
base: master
Choose a base branch
from
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
19 changes: 19 additions & 0 deletions qcr_force_sensor_ros/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
cmake_minimum_required(VERSION 2.8.3)
project(qcr_force_sensor_ros)

find_package(catkin REQUIRED)

catkin_python_setup()

catkin_package(
)

file(GLOB SCRIPT_PROGRAMS node_scripts/*.py)
catkin_install_python(PROGRAMS ${SCRIPT_PROGRAMS}
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/node_scripts
)

install(DIRECTORY config launch
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
USE_SOURCE_PERMISSIONS
)
29 changes: 29 additions & 0 deletions qcr_force_sensor_ros/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
# qcr_force_sensor_ros

ROS driver package for QCR force sensor.

## How to install

- Install dependency of `qcr_force_sensor_ros` (e.g., by `rosdep install`) and build `qcr_force_sensor_ros` (e.g., by `catkin build`)
- See http://wiki.ros.org/rosdep#Install_dependency_of_all_packages_in_the_workspace for `rosdep` usage

For example:
```bash
mkdir -p ~/ws_qcr_force_sensor_ros/src
cd ~/ws_qcr_force_sensor_ros/src
git clone https://github.com/pazeshun/jsk_3rdparty.git -b qcr_force_sensor_ros
rosdep install -y -r --ignore-src --from-paths jsk_3rdparty/qcr_force_sensor_ros
cd ..
catkin build qcr_force_sensor_ros
source ~/ws_qcr_force_sensor_ros/devel/setup.bash # Do this every time you open a new terminal
```

## How to use

```bash
# First, plug in your sensor and give permission to its device file (e.g., "sudo chmod a+rw /dev/ttyUSB0").
# Then...
roslaunch qcr_force_sensor_ros sample.launch port:=/dev/ttyUSB0
# On another terminal
rosservice call /qcr_force_sensor_driver/calibrate_offset "{}" # Do not touch or move the sensor until this command finishes. Call this service every time you want to remove sensor offset
```
134 changes: 134 additions & 0 deletions qcr_force_sensor_ros/config/rviz/sample.rviz
Original file line number Diff line number Diff line change
@@ -0,0 +1,134 @@
Panels:
- Class: rviz/Displays
Help Height: 78
Name: Displays
Property Tree Widget:
Expanded:
- /Global Options1
- /Status1
Splitter Ratio: 0.5
Tree Height: 549
- Class: rviz/Selection
Name: Selection
- Class: rviz/Tool Properties
Expanded:
- /2D Pose Estimate1
- /2D Nav Goal1
- /Publish Point1
Name: Tool Properties
Splitter Ratio: 0.5886790156364441
- Class: rviz/Views
Expanded:
- /Current View1
Name: Views
Splitter Ratio: 0.5
- Class: rviz/Time
Experimental: false
Name: Time
SyncMode: 0
SyncSource: ""
Preferences:
PromptSaveOnExit: true
Toolbars:
toolButtonStyle: 2
Visualization Manager:
Class: ""
Displays:
- Alpha: 0.5
Cell Size: 1
Class: rviz/Grid
Color: 160; 160; 164
Enabled: true
Line Style:
Line Width: 0.029999999329447746
Value: Lines
Name: Grid
Normal Cell Count: 0
Offset:
X: 0
Y: 0
Z: 0
Plane: XY
Plane Cell Count: 10
Reference Frame: <Fixed Frame>
Value: true
- Alpha: 1
Arrow Width: 0.5
Class: rviz/WrenchStamped
Enabled: true
Force Arrow Scale: 2
Force Color: 204; 51; 51
Hide Small Values: true
History Length: 1
Name: WrenchStamped
Topic: /qcr_force_sensor_driver/output/wrench
Torque Arrow Scale: 20
Torque Color: 204; 204; 51
Unreliable: false
Value: true
Enabled: true
Global Options:
Background Color: 255; 255; 255
Default Light: true
Fixed Frame: qcr_force_sensor
Frame Rate: 30
Name: root
Tools:
- Class: rviz/Interact
Hide Inactive Objects: true
- Class: rviz/MoveCamera
- Class: rviz/Select
- Class: rviz/FocusCamera
- Class: rviz/Measure
- Class: rviz/SetInitialPose
Theta std deviation: 0.2617993950843811
Topic: /initialpose
X std deviation: 0.5
Y std deviation: 0.5
- Class: rviz/SetGoal
Topic: /move_base_simple/goal
- Class: rviz/PublishPoint
Single click: true
Topic: /clicked_point
Value: true
Views:
Current:
Class: rviz/Orbit
Distance: 10
Enable Stereo Rendering:
Stereo Eye Separation: 0.05999999865889549
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Focal Point:
X: 0
Y: 0
Z: 0
Focal Shape Fixed Size: true
Focal Shape Size: 0.05000000074505806
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.009999999776482582
Pitch: 0.785398006439209
Target Frame: <Fixed Frame>
Value: Orbit (rviz)
Yaw: 0.785398006439209
Saved: ~
Window Geometry:
Displays:
collapsed: false
Height: 846
Hide Left Dock: false
Hide Right Dock: false
QMainWindow State: 000000ff00000000fd000000040000000000000156000002b0fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000002b0000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002b0fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d000002b0000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004f30000003efc0100000002fb0000000800540069006d00650100000000000004f3000002eb00fffffffb0000000800540069006d0065010000000000000450000000000000000000000282000002b000000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection:
collapsed: false
Time:
collapsed: false
Tool Properties:
collapsed: false
Views:
collapsed: false
Width: 1267
X: 60
Y: 27
27 changes: 27 additions & 0 deletions qcr_force_sensor_ros/launch/sample.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
<launch>

<arg name="driver_name" default="qcr_force_sensor_driver" />
<arg name="port" default="/dev/ttyUSB0" />
<arg name="baud" default="115200" />
<arg name="n_per_hz" default="0.0000286" />
<arg name="offset_calib_sample_number" default="300" />
<arg name="sensor_frame_id" default="qcr_force_sensor" />
<arg name="rviz" default="true" />

<include file="$(find qcr_force_sensor_ros)/launch/sensor_driver.launch">
<arg name="driver_name" value="$(arg driver_name)" />
<arg name="port" value="$(arg port)" />
<arg name="baud" value="$(arg baud)" />
<arg name="n_per_hz" default="$(arg n_per_hz)" />
<arg name="offset_calib_sample_number" default="$(arg offset_calib_sample_number)" />
<arg name="sensor_frame_id" default="$(arg sensor_frame_id)" />
</include>

<group if="$(arg rviz)">
<node name="rviz"
pkg="rviz" type="rviz"
args="-d $(find qcr_force_sensor_ros)/config/rviz/sample.rviz">
</node>
</group>

</launch>
22 changes: 22 additions & 0 deletions qcr_force_sensor_ros/launch/sensor_driver.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,22 @@
<launch>

<arg name="driver_name" default="qcr_force_sensor_driver" />
<arg name="port" default="/dev/ttyUSB0" />
<arg name="baud" default="115200" />
<arg name="n_per_hz" default="0.0000286" />
<arg name="offset_calib_sample_number" default="300" />
<arg name="sensor_frame_id" default="qcr_force_sensor" />

<node name="$(arg driver_name)"
pkg="qcr_force_sensor_ros" type="sensor_driver.py"
output="screen">
<rosparam subst_value="true">
port: $(arg port)
baud: $(arg baud)
n_per_hz: $(arg n_per_hz)
offset_calib_sample_number: $(arg offset_calib_sample_number)
sensor_frame_id: $(arg sensor_frame_id)
</rosparam>
</node>

</launch>
91 changes: 91 additions & 0 deletions qcr_force_sensor_ros/node_scripts/sensor_driver.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,91 @@
#!/usr/bin/env python

import serial
import threading

import rospy
from geometry_msgs.msg import WrenchStamped
from std_srvs.srv import Empty
from std_srvs.srv import EmptyResponse


class SensorDriver(object):

def __init__(self):
super(SensorDriver, self).__init__()
port = rospy.get_param('~port', '/dev/ttyUSB0')
baud = rospy.get_param('~baud', 115200)
self.n_per_hz = rospy.get_param('~n_per_hz', 0.0000286)
self.calib_sample_num = rospy.get_param(
'~offset_calib_sample_number', 300)
self.sensor_frame_id = rospy.get_param(
'~sensor_frame_id', 'qcr_force_sensor')
rospy.loginfo('port=%s, baud=%s', port, baud)
self.ser = serial.Serial(port, baudrate=baud)
self.offset = 0.0
self.last_raw_val = None
self.last_stamp = None
self.lock = threading.Lock()
self.calib_srv = rospy.Service(
'~calibrate_offset', Empty, self.calib_offset)
self.wrench_pub = rospy.Publisher(
'~output/wrench', WrenchStamped, queue_size=1)

def calib_offset(self, req):
rospy.loginfo(
'[{}] offset calibration started...'.format(
rospy.get_name()))

while self.last_stamp is None:
rospy.sleep(0.00001)

with self.lock:
last_stamp_in_vals = self.last_stamp
vals = [self.last_raw_val]
for i in range(self.calib_sample_num):
while self.last_stamp <= last_stamp_in_vals:
rospy.sleep(0.00001)

with self.lock:
last_stamp_in_vals = self.last_stamp
vals.append(self.last_raw_val)

with self.lock:
self.offset = sum(vals) / float(len(vals))
rospy.loginfo(
'[{}] offset calibration finished. Offset: {}'.format(
rospy.get_name(), self.offset))

return EmptyResponse()

def run(self):
self.ser.readline() # Flush first data because it is hardly complete.
# Here we assume this process is just after initialization of ser.
# Otherwise data in input buffer become too many and collapse.
# Flushing them is difficult:
# https://github.com/pyserial/pyserial/issues/344
while not rospy.is_shutdown():
raw_val = float(self.ser.readline())
with self.lock:
self.last_raw_val = raw_val
self.last_stamp = rospy.Time.now() # Get timestamp ASAP after message arrival

force = (raw_val - self.offset) * self.n_per_hz

# Publish force as WrenchStamped
wrench_msg = WrenchStamped()
wrench_msg.header.stamp = self.last_stamp
wrench_msg.header.frame_id = self.sensor_frame_id
wrench_msg.wrench.force.x = force
wrench_msg.wrench.force.y = 0
wrench_msg.wrench.force.z = 0
wrench_msg.wrench.torque.x = 0
wrench_msg.wrench.torque.y = 0
wrench_msg.wrench.torque.z = 0
self.wrench_pub.publish(wrench_msg)


if __name__ == '__main__':
rospy.init_node('qcr_force_sensor_driver')
app = SensorDriver()
app.run()
21 changes: 21 additions & 0 deletions qcr_force_sensor_ros/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,21 @@
<?xml version="1.0"?>
<package format="3">
<name>qcr_force_sensor_ros</name>
<version>2.1.14</version>
<description>ROS driver package for QCR force sensor</description>

<maintainer email="[email protected]">Shun Hasegawa</maintainer>
<maintainer email="[email protected]">Kei Okada</maintainer>
<author email="[email protected]">Shun Hasegawa</author>

<license>BSD</license>

<buildtool_depend>catkin</buildtool_depend>
<exec_depend condition="$ROS_PYTHON_VERSION == 2">python-serial</exec_depend>
<exec_depend condition="$ROS_PYTHON_VERSION == 3">python3-serial</exec_depend>
<exec_depend>rospy</exec_depend>
<exec_depend>std_srvs</exec_depend>

<export>
</export>
</package>
8 changes: 8 additions & 0 deletions qcr_force_sensor_ros/setup.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
#!/usr/bin/env python

from setuptools import setup
from catkin_pkg.python_setup import generate_distutils_setup

d = generate_distutils_setup()

setup(**d)