Skip to content

Commit

Permalink
Merge pull request #13 from jsaltducaju/master
Browse files Browse the repository at this point in the history
Adds unit tests
  • Loading branch information
matthias-mayr authored Nov 7, 2023
2 parents 18e2a3f + 4558a04 commit 7eb6f7a
Show file tree
Hide file tree
Showing 15 changed files with 666 additions and 31 deletions.
10 changes: 8 additions & 2 deletions .github/workflows/build_code.yml
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
name: CI

on: [push]
on: [push, pull_request]

jobs:
build-code:
Expand Down Expand Up @@ -29,4 +29,10 @@ jobs:
catkin init
catkin config --extend /opt/ros/$ROS_DISTRO
catkin build
echo "Compile complete."
echo "Compile complete."
- name: Run tests
shell: bash
run: |
source /opt/ros/$ROS_DISTRO/setup.bash
cd catkin_ws
catkin test
19 changes: 19 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
cmake_minimum_required(VERSION 2.8.3)
cmake_policy(SET CMP0048 NEW) # Version not in project() command
project(cartesian_impedance_controller)

find_package(Boost 1.49 REQUIRED)
Expand Down Expand Up @@ -98,3 +99,21 @@ install(DIRECTORY include/${PROJECT_NAME}/
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
FILES_MATCHING PATTERN "*.h"
PATTERN ".svn" EXCLUDE)

## Testing
if (CATKIN_ENABLE_TESTING)
# Base library tests
find_package(rostest REQUIRED)
add_rostest_gtest(base_tests test/base.test test/base_tests.cpp)
target_link_libraries(base_tests ${PROJECT_NAME} ${Eigen3_LIBRARIES} ${catkin_LIBRARIES})

# ROS basic tests
add_rostest_gtest(ros_tests test/ros.test test/ros_tests.cpp)
target_link_libraries(ros_tests ${PROJECT_NAME} ${Eigen3_LIBRARIES} ${catkin_LIBRARIES})

# ROS functionality tests
add_rostest_gtest(ros_func_tests test/ros_func.test test/ros_func_tests.cpp)
target_link_libraries(ros_func_tests ${PROJECT_NAME} ${Eigen3_LIBRARIES} ${catkin_LIBRARIES})
endif()


Empty file modified cfg/stiffness.cfg
100755 → 100644
Empty file.
Original file line number Diff line number Diff line change
Expand Up @@ -284,4 +284,4 @@ namespace cartesian_impedance_controller
void updateFilteredWrench();
};

} // namespace cartesian_impedance_controller
} // namespace cartesian_impedance_controller
51 changes: 30 additions & 21 deletions package.xml
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<package>
<package format="3">
<name>cartesian_impedance_controller</name>
<version>1.0.0</version>
<version>1.1.0</version>
<description>
A Cartesian Impedance controller implementation
</description>
Expand All @@ -9,6 +9,7 @@

<author>Matthias Mayr</author>
<author>Oussama Chouman</author>
<author>Julian Salt Ducaju</author>

<buildtool_depend>catkin</buildtool_depend>

Expand All @@ -32,27 +33,35 @@
<build_depend>tf_conversions</build_depend>
<build_depend>trajectory_msgs</build_depend>

<run_depend>actionlib</run_depend>
<run_depend>actionlib_msgs</run_depend>
<run_depend>control_msgs</run_depend>
<run_depend>controller_interface</run_depend>
<run_depend>controller_manager</run_depend>
<run_depend>dynamic_reconfigure</run_depend>
<run_depend>eigen_conversions</run_depend>
<run_depend>geometry_msgs</run_depend>
<run_depend>hardware_interface</run_depend>
<run_depend>message_runtime</run_depend>
<run_depend>pluginlib</run_depend>
<run_depend>realtime_tools</run_depend>
<run_depend>roscpp</run_depend>
<run_depend>sensor_msgs</run_depend>
<run_depend>std_msgs</run_depend>
<run_depend>tf</run_depend>
<run_depend>tf_conversions</run_depend>
<run_depend>trajectory_msgs</run_depend>
<exec_depend>actionlib</exec_depend>
<exec_depend>actionlib_msgs</exec_depend>
<exec_depend>control_msgs</exec_depend>
<exec_depend>controller_interface</exec_depend>
<exec_depend>controller_manager</exec_depend>
<exec_depend>dynamic_reconfigure</exec_depend>
<exec_depend>eigen_conversions</exec_depend>
<exec_depend>geometry_msgs</exec_depend>
<exec_depend>hardware_interface</exec_depend>
<exec_depend>message_runtime</exec_depend>
<exec_depend>pluginlib</exec_depend>
<exec_depend>realtime_tools</exec_depend>
<exec_depend>roscpp</exec_depend>
<exec_depend>sensor_msgs</exec_depend>
<exec_depend>std_msgs</exec_depend>
<exec_depend>tf</exec_depend>
<exec_depend>tf_conversions</exec_depend>
<exec_depend>trajectory_msgs</exec_depend>

<export>
<export>
<!-- Other tools can request additional information be placed here -->
<controller_interface plugin="${prefix}/controller_plugins.xml"/>
</export>

<test_depend>gtest</test_depend>
<test_depend>eigen</test_depend>
<test_depend>roscpp</test_depend>
<test_depend>rostest</test_depend>
<test_depend>geometry_msgs</test_depend>
<test_depend>std_msgs</test_depend>
<test_depend>dynamic_reconfigure</test_depend>
</package>
46 changes: 46 additions & 0 deletions res/config/example_controller.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,46 @@
# An example configuration that works with the example
#
# It is also used in the integration tests

CartesianImpedance_trajectory_controller:
type: cartesian_impedance_controller/CartesianImpedanceController
joints: # Joints to control
- joint1
- joint2
- joint3
- joint4
- joint5
- joint6
- joint7
end_effector: tool0 # Link to control arm in
update_frequency: 500 # Controller update frequency in Hz
dynamic_reconfigure: true # Starts dynamic reconfigure server
handle_trajectories: true # Accept traj., e.g. from MoveIt
robot_description: /robot_description # In case of a varying name
wrench_ee_frame: tool0 # Default frame for wrench commands
delta_tau_max: 1.0 # Max. commanded torque diff between steps in Nm
filtering: # Update existing values (0.0 1.0] per s
nullspace_config: 0.1 # Nullspace configuration filtering
pose: 0.1 # Reference pose filtering
stiffness: 0.1 # Cartesian and nullspace stiffness
wrench: 0.1 # Commanded torque
verbosity:
verbose_print: false # Enables additional prints
state_msgs: true # Messages of controller state
tf_frames: true # Extra tf frames

joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: 500

# Settings for ros_control hardware interface
hardware_interface:
control_freq: 500 # in Hz
joints:
- joint1
- joint2
- joint3
- joint4
- joint5
- joint6
- joint7
41 changes: 41 additions & 0 deletions res/launch/examples.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
<launch>
<!-- Configuration -->
<arg name="gazebo_gui" default="true"/>
<arg name="gzclient" default="true"/>
<arg name="debug" default="false"/>

<!-- Load robot_description to parameter server -->
<param name="/robot_description"
command="$(find xacro)/xacro '$(find cartesian_impedance_controller)/res/urdf/robot.urdf.xacro'" />

<!-- Robot state publisher -->
<node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher">
<param name="publish_frequency" type="double" value="50.0" />
<param name="tf_prefix" type="string" value="" />
</node>

<!-- Joint state publisher -->
<node name="joint_state_controller_spawner" pkg="controller_manager" type="spawner" args="joint_state_controller" respawn="false" output="screen"/>

<!-- Load controller configuration -->
<rosparam file="$(find cartesian_impedance_controller)/res/config/example_controller.yaml" command="load"></rosparam>

<!-- Spawn controllers -->
<node name="controller_spawner" pkg="controller_manager" type="spawner"
args="CartesianImpedance_trajectory_controller"
/>

<!-- Loads the Gazebo world -->
<include if="$(arg gzclient)"
file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="debug" value="$(arg debug)" />
<arg name="gui" value="$(arg gazebo_gui)" />
<arg name="paused" value="false"/>
<arg name="use_sim_time" value="true"/>
<arg name="headless" value="false"/>
</include>

<!-- Run a python script to send a service call to gazebo_ros to spawn a URDF robot -->
<node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen"
args="-urdf -model robot -param robot_description"/>
</launch>
126 changes: 126 additions & 0 deletions res/urdf/robot.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,126 @@
<?xml version="1.0"?>
<robot name="robot" xmlns:xacro="http://ros.org/wiki/xacro">

<!-- Properties for materials -->
<material name="blue">
<color rgba="0 0 0.8 1"/>
</material>
<material name="orange">
<color rgba="1.0 0.423529411765 0.0392156862745 1.0"/>
</material>

<!-- Connect to world -->
<link name="world" />
<joint name="world_joint" type="fixed">
<parent link="world" />
<child link = "base_link" />
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
</joint>

<!-- Base link -->
<link name="base_link">
<visual>
<geometry>
<cylinder length="0.1" radius="0.05"/>
</geometry>
<material name="blue"/>
</visual>
<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="1"/>
<inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01"/>
</inertial>
</link>

<!-- Joint and link definitions -->
<xacro:macro name="rotational_joint" params="prefix parent child xyz rpy length x y z r p yo">
<joint name="${prefix}" type="revolute">
<origin xyz="${xyz}" rpy="${rpy}"/>
<parent link="${parent}"/>
<child link="${child}"/>
<axis xyz="0 0 1"/>
<limit lower="-2.967" upper="2.967" effort="300" velocity="2.5"/>
</joint>

<link name="${child}">
<visual name="joint">
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<sphere radius="0.05"/>
</geometry>
<material name="orange"/>
</visual>
<visual name="link">
<origin xyz="${x} ${y} ${z}" rpy="${r} ${p} ${yo}" />
<geometry>
<cylinder length="${length}" radius="0.03"/>
</geometry>
<material name="blue"/>
</visual>
<inertial>
<!-- Generic inertial properties, adjust for accuracy -->
<origin xyz="${x} ${y} ${z}" rpy="${r} ${p} ${yo}" />
<mass value="1"/>
<inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01"/>
</inertial>
</link>

<!-- Transmission -->
<transmission name="${prefix}_transmission">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${prefix}">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="${prefix}_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>


<!-- Gazebo configuration for the joint -->
<gazebo reference="${prefix}">
<dynamics damping="0.01" friction="0.02"/>
</gazebo>

<gazebo reference="${child}">
<turnGravityOff>true</turnGravityOff>
</gazebo>
</xacro:macro>

<!-- Chain of joints and links -->
<xacro:rotational_joint prefix="joint1" parent="base_link" child="link1" xyz="0 0 0.35" rpy="0 0 0" length="0.333" x="0" y="0" z="-0.175" r="0" p="0" yo="0"/>
<xacro:rotational_joint prefix="joint2" parent="link1" child="link2" xyz="0 0 0" rpy="0 -1.5708 0" length="0.3" x="0" y="0.15" z="0" r="-1.5708" p="0" yo="0"/>
<xacro:rotational_joint prefix="joint3" parent="link2" child="link3" xyz="0 0.3 0" rpy="0 1.5708 0" length="0.0" x="0" y="0" z="0" r="-1.5708" p="0" yo="0"/>
<xacro:rotational_joint prefix="joint4" parent="link3" child="link4" xyz="0 0 0" rpy="0 1.5708 0" length="0.4" x="0" y="0" z="0.2" r="0" p="0" yo="0"/>
<xacro:rotational_joint prefix="joint5" parent="link4" child="link5" xyz="0 0 0.4" rpy="0 -1.5708 0" length="0" x="0" y="0" z="0" r="0" p="1.5708" yo="0"/>
<xacro:rotational_joint prefix="joint6" parent="link5" child="link6" xyz="0 0 0" rpy="0 1.5708 0" length="0.1" x="0.05" y="0" z="0" r="0" p="1.5708" yo="0"/>
<xacro:rotational_joint prefix="joint7" parent="link6" child="link7" xyz="0.1 0 0" rpy="0 1.5708 0" length="0.107" x="0" y="0" z="0.05035" r="0" p="0" yo="0"/>

<!-- Joint connecting the last link and the end-effector -->
<joint name="tool0_joint" type="fixed">
<parent link="link7"/>
<child link="tool0"/>
<origin xyz="0 0 0.107" rpy="0 0 0"/>
</joint>

<!-- End-effector link -->
<link name="tool0">
<visual>
<geometry>
<sphere radius="0.05"/>
</geometry>
<material name="blue"/>
</visual>
</link>



<!-- Gazebo ROS Control plugin -->
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so" />
</gazebo>



</robot>

Loading

0 comments on commit 7eb6f7a

Please sign in to comment.