Skip to content

Instantly share code, notes, and snippets.

View felixvd's full-sized avatar

Felix von Drigalski felixvd

  • Mujin Inc.
  • Tokyo, Japan
View GitHub Profile
@felixvd
felixvd / gist:87ce31d7f1053410186d70b5a960a213
Created July 26, 2020 18:13
Valgrind output 2020-7-27
[ INFO] [1595786409.984394846]: Moving to bottom of box with cylinder tip
==2459== Invalid read of size 16
==2459== at 0x3365BB: _mm_loadu_pd (emmintrin.h:131)
==2459== by 0x3365BB: double __vector(2) Eigen::internal::ploadu<double __vector(2)>(Eigen::internal::unpacket_traits<double __vector(2)>::type const*) (PacketMath.h:336)
==2459== by 0x378616: ploadt<__vector(2) double, 0> (GenericPacketMath.h:465)
==2459== by 0x378616: double __vector(2) Eigen::internal::mapbase_evaluator<Eigen::Block<Eigen::Matrix<double, 4, 4, 0, 4, 4> const, 3, 3, false>, Eigen::Matrix<double, 3, 3, 0, 3, 3> >::packet<0, double __vector(2)>(long, long) const (CoreEvaluators.h:860)
==2459== by 0x3B7D21: Eigen::internal::etor_product_packet_impl<0, 1, Eigen::internal::evaluator<Eigen::Block<Eigen::Matrix<double, 4, 4, 0, 4, 4> const, 3, 3, false> >, Eigen::internal::evaluator<Eigen::Block<Eigen::Matrix<double, 4, 4, 0, 4, 4> const, 3, 3, false> >, double __vector(2), 0>::run(long, long, Eigen::internal::evaluator<Eigen
@felixvd
felixvd / robotiq_control.py
Created August 6, 2020 12:09
Debugging notes for Modbus RTU/TCP for Robotiq gripper
#!/usr/bin/env python
import os
import sys
import socket
from math import ceil
import time
import threading
from pymodbus.client.sync import ModbusTcpClient
from pymodbus.register_read_message import ReadInputRegistersResponse
@felixvd
felixvd / cmodel_urcap.py
Created August 20, 2020 02:54
Robotiq gripper control node for UR-mounted grippers with URCap installed on the pendant
"""Module to control Robotiq's gripper 2F-85."""
# BASED ON: https://dof.robotiq.com/discussion/1962/programming-options-ur16e-2f-85#latest
# ROS/Python2 port by felixvd
import socket
import threading
import time
from enum import Enum
# Added for ROS
----------------------------------------------------------------------------------------------------------------------
Profile: default
Extending: [explicit] /opt/ros/melodic
Workspace: /root/linked_ws_moveit
----------------------------------------------------------------------------------------------------------------------
Build Space: [exists] /root/linked_ws_moveit/build
Devel Space: [exists] /root/linked_ws_moveit/devel
Install Space: [unused] /root/linked_ws_moveit/install
Log Space: [missing] /root/linked_ws_moveit/logs
Source Space: [exists] /root/linked_ws_moveit/src
@felixvd
felixvd / gist:1915b3aa511262b0950a53d2bd11d4b9
Last active September 1, 2020 15:32
clang-tidy terminal output
This file has been truncated, but you can view the full file.
root@felix-OMEN-by-HP-Desktop-PC-880-p1xx:~/ws_moveit# catkin build
-------------------------------------------------------------------------------------------------
Profile: default
Extending: [explicit] /opt/ros/melodic
Workspace: /root/ws_moveit
-------------------------------------------------------------------------------------------------
Build Space: [exists] /root/ws_moveit/build
Devel Space: [exists] /root/ws_moveit/devel
Install Space: [exists] /root/ws_moveit/install
Log Space: [exists] /root/ws_moveit/logs
@felixvd
felixvd / activate_ros_control_on_ur.cpp
Created October 1, 2020 01:32
Boilerplate code to activate ROS control script on UR robots ( https://github.com/UniversalRobots/Universal_Robots_ROS_Driver )
# Software License Agreement (BSD License)
#
# Copyright (c) 2020, OMRON SINIC X
# 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
@felixvd
felixvd / ur5e_problem_trajectory.yaml
Last active October 8, 2020 12:06
ur5e_problem_trajectory
!!python/object/new:trajectory_msgs.msg._JointTrajectory.JointTrajectory {state: [
!!python/object/new:std_msgs.msg._Header.Header {state: [1, !!python/object/new:rospy.rostime.Time {
state: [1601987639, 899594068]}, world]}, [shoulder_pan_joint, shoulder_lift_joint,
elbow_joint, wrist_1_joint, wrist_2_joint, wrist_3_joint],
[!!python/object/new:trajectory_msgs.msg._JointTrajectoryPoint.JointTrajectoryPoint {
state: [!!python/tuple [2.981921261631558, -1.27472656822998, 1.3204057526082944,
-1.6164710215873699, 3.075542515700016, -6.91763185490812e-07], !!python/tuple [],
!!python/tuple [], !!python/tuple [], !!python/object/new:genpy.rostime.Duration {
state: [0, 20000000]}]}, !!python/object/new:trajectory_msgs.msg._JointTrajectoryPoint.JointTrajectoryPoint {
state: [!!python/tuple [2.9811632914464603, -1.2739736220142608, 1.3194444408261852,
@felixvd
felixvd / cartesian_path_service_capability.cpp
Last active October 22, 2020 04:27
Comparing time parametrizations
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2012, Willow Garage, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
@felixvd
felixvd / example_scene.urdf.xacro
Created November 2, 2020 15:48
URDF with two differently prefixed UR robots
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro"
name="example_scene" >
<!-- robot arms -->
<xacro:ur5_robot prefix="a_bot_" joint_limited="false"
shoulder_pan_lower_limit="${-pi}" shoulder_pan_upper_limit="${pi}"
shoulder_lift_lower_limit="${-pi}" shoulder_lift_upper_limit="${pi}"
elbow_joint_lower_limit="0.0" elbow_joint_upper_limit="${pi}"
wrist_1_lower_limit="${-pi}" wrist_1_upper_limit="${pi}"
@felixvd
felixvd / ur_axis_angle_to_quat.py
Created July 6, 2021 03:21
Convert between ROS Quaternion and UR (Universal Robot) axis-angle rotation representation
from math import pi, cos, sin, sqrt, atan2
def norm2(a, b, c=0.0):
return sqrt(a**2 + b**2 + c**2)
def ur_axis_angle_to_quat(axis_angle):
# https://en.wikipedia.org/wiki/Axis%E2%80%93angle_representation#Unit_quaternions
angle = norm2(*axis_angle)
axis_normed = [axis_angle[0]/angle, axis_angle[1]/angle, axis_angle[2]/angle]
s = sin(angle/2)