Giter Site home page Giter Site logo

krishauser / klampt Goto Github PK

View Code? Open in Web Editor NEW
361.0 18.0 93.0 134.88 MB

Kris' Locomotion and Manipulation Planning Toolkit

License: BSD 3-Clause "New" or "Revised" License

CMake 0.33% C++ 58.60% QMake 0.02% Makefile 0.04% C 0.70% Python 37.64% Shell 0.01% Batchfile 0.01% HTML 0.24% Dockerfile 0.01% JavaScript 0.38% CSS 0.01% SWIG 2.02%

klampt's Introduction

Klamp't Build Status

Klamp't image

Klamp't (Kris' Locomotion and Manipulation Planning Toolbox) is an open-source, cross-platform software package for robot modeling, simulating, planning, optimization, and visualization. It aims to provide an accessible, wide range of programming tools for learning robotics, analyzing robots, developing algorithms, and prototyping intelligent behaviors. It has particular strengths in robot manipulation and locomotion.

Historically, it began development at Indiana University since 2009 primarily as a research platform. Since then, it has been adopted in education and research labs around the world.

More information can be found on the Klamp't website (http://klampt.org)

Features

  • Unified C++ and Python package for robot modeling, kinematics, dynamics, control, motion planning, simulation, and visualization.
  • Interoperable with Robot Operating System (ROS 1) and Open Motion Planning Library (OMPL).
  • Stable file formats and tooling to save, load, and visualize robots (URDF), meshes, configurations, trajectories, poses, and more.
  • Built-in conversions to and from Numpy, JSON, ROS 1, Open3D, trimesh, PyTorch, and Sympy objects (in the Python API).
  • Many geometry types implemented, including meshes, point clouds, signed distance functions, occupancy grids, geometric primitives, and convex polytopes. Collision, distance, and ray-casting queries are available between most pairs of geometry types.
  • Many sampling-based motion planners implemented (RRT, EST, SBL, RRT*, Lazy-RRG*, Lazy-PRM*, and more).
  • Fast trajectory optimization routines.
  • Real-time motion planning routines.
  • Forward and inverse kinematics, forward and inverse dynamics.
  • Contact mechanics computations (force closure, support polygons, stability of rigid bodies and actuated robots).
  • Planning models are fully decoupled from simulation models. This helps simulate uncertainty and modeling errors.
  • Robust rigid body simulation supporting triangle-soup and point cloud collisions. No need to create convex decompositions!
  • Simulation of PID controlled, torque controlled, and velocity controlled motors.
  • Simulation of various sensors including cameras, depth sensors, laser range finders, gyroscopes, force/torque sensors, and accelerometers.
  • Works on several platforms:
    • *nux environments (x86_64, i686, Aarch64)
    • Windows
    • MacOS up to 11+
    • Google Colab

Note: newer versions of MacOS (11+) dropped OpenGL 2.0 support, so Klampt may not build. We're currently looking for alternative cross-platform graphics engines.

(Please let us know if you are able to compile on other platforms in order to help us support them in the future.)

Installation

Quick start (Python API only):

  • pip install klampt (or pip3 install klampt)

To run a visualization (you may need to replace pip with pip3 and python with python3):

  • pip install PyOpenGL
  • pip install PyQt5
  • git clone http://github.com/krishauser/Klampt-examples (this is needed to run example programs)
  • cd Klampt-examples/Python3/demos
  • python gl_vis.py

Installation instructions are also available for

Klamp't works best when it is installed on your local machine, but it can also be run online through your web browser using Google Colab or Binder (or any other Jupyterhub server).

  • Google Colab Open In Colab
  • Binder Open in Binder

Note that the UI functionality is drastically limited compared to a local installation.

Documentation

Python Manual and API Documentation

C++ Manual

API documentation is available here

Reporting bugs and getting help

If you identify a programming bug or issue, please raise them on this Github site. If you have general questions installing or programming with Klamp't, please ask them on the Klamp't forum, which is available on GitQ: https://gitq.com/krishauser/Klampt.

Version history

master (8/13/2024)

Note: If you have a pip installed Klampt at version 0.9.2, you may get the latest updates by cloning the Git repo, then run cd Klampt/Python; python patch_a_pip_install.py. This provides all of the Python API updates listed below without needing to build from source.

0.9.2 (8/13/2024)

  • Python API: pip packages now built with Numpy 2+.
  • Python API: Improved calibration routines in klampt.model.calibrate.
  • Python API: Added surface sampling and vertex normals to klampt.model.geometry.
  • Python API: Added visibility fraction determination to klampt.model.sensing.
  • Python API: Added conversions of meshes to/from the trimesh library in klampt.io.trimesh_convert.
  • Python API: Fixed bug in SO3/SE3 Hermite velocity interpolation. Now using extrinsic angular velocity representation as tangent vectors.
  • Python API: Mouse wheel events can now be captured in visualization (Qt and GLUT backends).

0.9.1 (10/30/2023)

  • Removed GLUI dependency in default build mode.
  • Updated GLEW to 2.1.0.
  • Builds for Linux Python 3.10+ are now working again. (Mac OS 11+ support is still TBD.)
  • IK solver now has a minimization mode and a prioritized solve mode.
  • Fixed problem with custom textures being unloaded after a mesh is transformed.
  • Fixed bug in simulation of affine joints when the joint angle can go negative. Also, internal affine transmission coupling is simulated in a fashion that's sensitive to the driver's PID constants.
  • Minor performance improvements to IK; API for getting subset of Jacobian columns.
  • Python API: substantial performance improvements to camera image retrieval (camera_to_images).
  • Python API: new calls for getting subset of Jacobian columns.
  • Python API: Added types.convert generic utility function.
  • Python API: Fixed bugs with vis module picker. Also, appearances can now have a tint set to match the C++ API.
  • Python API: Bug fixes and type hints in coordinates module.
  • Python API: Bug fix with cost evaluation in EmbeddedCSpace working on the embedded vectors (e.g., causing problems with outputs from makePlan)
  • Python API: Removed klampt_path app and added functionality to klampt_resource app instead.
  • Python API: Switch from deprecated pkg_resources to importlib for IO to resource files.
  • Python API: Docs now instruct users to use pip install . rather than deprecated Setuptools.

0.9 (1/15/2022)

  • Python API: type hints are available throughout the SWIG interface and in many native Python functions.
  • Python API: direct Numpy interface speeds up large data copies. Tests indicate ~6x speedup (45ms->7.5ms) for getting a simulated sensor image (SimRobotSensor.getMeasurements()), ~80x speedup (160ms->2ms) for converting images to point clouds (PointCloud.setDepthImage/setRGBDImages), and 20x speedup (200ms->10ms) for converting a Numpy array to a point cloud (tested on 640x480 images).
  • Python API: global functions and many classes in the the klampt.vis module now conform to PEP8 naming conventions. Old non-conformant functions produce a DeprecationWarning and will be removed in the future. (Run your code with python -W all to see these warnings.)
  • Python API: major updates to the Klampt control package, including the new klampt_control utility that lets you control your robots in real time. (API-breaking change)
  • Python API: standardization of robot semantic information under a RobotInfo class in klampt.model.robotinfo. Supported by klampt_control and klampt_sim. Future planners and system integration utilities will use this structure.
  • Python API: klampt_resource script added which allows transfer and conversions of resources from the command line. klampt_thumbnails has been removed since all thumbnail functionality has been moved into klampt_resource.
  • Python API: new system integration utilities, such as calibration (klampt.model.calibrate) and workspace calculation (klampt.model.workspace).
  • Python API: textures on Appearances now fully supported.
  • Python API: fixed bug with setBackgroundImage(None)
  • C++ API: Everything added to the Klampt namespace. (API-breaking change!)
  • C++ API: Main modeling classes renamed to align with Python API, e.g. Robot->RobotModel, RobotWorld->WorldModel, WorldSimulation->Simulator, etc. (API-breaking change!)
  • Fixed bug saving/restoring simulation states.
  • Some geometries support slicing and ROI (region of interest) calculations. Slicing takes a slice of a geometry with a plane, and ROI calculations determine a region of interest of the geometry. Meshes and point clouds are supported.
  • Polygon and ConvexHull geometries now support ray casting.
  • Projection-mapping for Appearances now supported.

0.8.7 (5/25/2021)

  • Fixed bug in simulation of affine joints when the joint angle can go negative. Also, internal affine transmission coupling is simulated in a fashion that's sensitive to the driver's PID constants.
  • URDF import can now import multiple collision and visual geometries.
  • Python API: Workaround for Mac OSX Big Sur dropping support for OpenGL when importing PyOpenGL.
  • Python API: bug fixes for motion planning with affine drivers.
  • Python API: Added a function klampt.model.types.transfer() which transfers objects from one robot to another.
  • Python API: Added convenience functions in klampt.model.sensing for converting camera intrinsics between Klamp't cameras and openCV and numpy formats.
  • Minor bug fixes.

0.8.6 (1/27/2021)

  • Fixed bug drawing Group geometries.
  • RGBD sensors now have a long range for RGB information like actual cameras do, rather than clipping to the sensor's specified depth range.
  • URDF mimic joints are now respected.
  • Fixed bug loading non-square textures.
  • Fixed bug with SubRobotModel editing in vis.
  • Python API: Moved some recently added routines from klampt.model.sensor to klampt.model.geometry.
  • Python API: klampt.io.ros integration with LaserScan messages and SimCameraSensor publishing.
  • Python API: klampt.io.ros can now broadcast SimCameraSensor frames to ros.broadcast_tf.
  • Python API: Bug fix with SimRobotSensor.kinematicSimulate and multiple worlds.
  • Python API: Added visual editor for SimRobotSensor. Trajectory editor now has option to use RobotTrajectory interpolation.
  • Python API: Bug fixes for HTML and IPython visualizations. vis.debug() now works for these modes, and removing text now works. Misc bugs are also fixed in the Jupyter extension.
  • Python API: More thorough bounds checking in core C++ interface.
  • Python API: Used Pylance to squash lots of small bugs in infrequently used branches of the code.

0.8.5 (12/7/2020)

  • Fixed a few bad bugs in the pip release (klampt_browser crash; resource editor crash; HTML output with no animation; HTML output with custom entities).
  • More thorough integration of custom joints into the simulation, including reading from XML world files (see Klampt-examples/data/simulation_test_worlds/jointtest.xml.
  • XML world files' simulation tags can now refer to named robots, rigid objects, and terrains.
  • Conversions from geometries to VolumeGrids now respect the geometry's collision margin.
  • Supports emissive and specular colors in OpenGL views and XML world files now.
  • The "automass" signal in .rob files and .obj (rigid object) files can now accept a parameter indicating how much mass is concentrated at the surface vs the interior of the object.
  • A bug in the earlier automass inertia matrix calculation made inertias much larger than they should have been! This may require re-calibrating robot PID constants to avoid jittering. (This bug will not affect robot / object files that specify inertias matrices.)
  • Python API: Can now remesh triangle meshes, point clouds, and volume grids using Geometry3D.convert(self.type(),resolution).
  • Python API: Easy vis.snapshot API added.

0.8.3 (10/24/2020)

  • Convex hulls are a new geometry type. They support conversion from multiple geometry types and conversion to meshes, visualization, and fast convex hull-convex hull proximity queries. (Queries are not yet supported for convex hull vs anything else.)
  • Python API: Python 3 is now the default version used by Klamp't, and all further feature development will be focused on Python 3. The Python 2 version will receive occasional bug fixes but will be deprecated by the next version.
  • Python API: The visualization API has a unified interface between PyQT, PyOpenGL, Jupyter notebooks, and HTML output. This makes it easy to convert your OpenGL visualizations into shareable, animated web pages (with some caveats). Use vis.init() to select which visualization backend to use.
  • Python API: A new klampt.math.autodiff module supports taking derivatives of many Klamp't functions. This lets you use optimization for, say, trajectory optimization, deep learning, etc. A Pytorch binding is supported.
  • Python API: A new kinematic trajectory optimization toolbox is available, klampt.plan.kinetrajopt. This uses convex hulls to enforce collision constraints along a path.
  • Python API: A new colorization module, klampt.vis.colorize, makes it easy to color-code point clouds and meshes for classy visualizations.
  • Python API: The klampt.math.vis module now supports a debug function for one-line visualization, and a followCamera function that is helpful for making animations.
  • Python API: The Jupyter / HTML API backends are upgraded to use the latest version of three.js.
  • Python API: The klampt.math.symbolic now supports tensor derivatives (e.g., the derivative of vector w.r.t. a matrix).
  • Python API: the RobotModel class now exposes reduce and mount methods.
  • Python API: The IKObjective, Geometry3D, GeometricPrimitive, TriangleMesh, PointCloud, VolumeGrid, and ConvexHull classes can now be pickled. Geometry objects now have JSON loaders/savers.
  • Python API ray casting can now return an index of the triangle / point that was hit: Geometry3D.rayCast_ext. VolumeGrids now support ray casting.
  • Python API: Trajectory functionality has been enhanced. Can now do acceleration-bounded and velocity-bounded minimum-time interpolation, smoothed (Hermite-like) geodesic interpolation on manifolds. Hermite, SO(3), and SE(3) trajectories can now be saved/loaded to/from JSON.
  • Python API: [EXPERIMENTAL] Klamp't can now drive your robots with the new Python klampt.control module! The RobotInterfaceBase class provides a unified interface for working with real motor controllers. For example, if you build a robot with basic position-controlled servos, the RobotInterfaceCompleter class provides a unified interface for executing trajectories on servos, motion smoothing, emergency stops, and Cartesian control. Also, if you build a robot consisting of multiple parts, such as an arm and a gripper, you can perform coordinated control using the MultiRobotInterface class.
  • Python API: Added SimJoint class to enable creation of sliding / hinge / fixed joints between bodies in the simulator.
  • C++ API: Robot class and the Python RobotModel class have methods to reduce the number of DOFs of a robot that contains fixed DOFs.
  • Miscellaneous bug fixes, improvements to the docs.

0.8.2 (11/15/2019)

  • Can now load almost all files from URLs! Just use an http:// prefix to the filenames of worlds, robots, rigid objects, or geometries. This also works for resources in Python. (Resources in C++ are not done yet)
  • New mesh visualization shows smooth meshes and black silhouettes by default, making things look prettier.
  • Can now mount robots in URDF files (see tutorial for an example).
  • Added ability to specify cost functions in kinematic planning.
  • Added conversions to Numpy objects in Python API (klampt.io.numpy_convert)
  • Added much more ROS support in Python API (klampt.io.ros module).
  • Added conversions to Open3D objects in Python API (klampt.io.open3d_convert)
  • The Python loading API has changed to have a more complete list of types and file extensions.
  • Fixed some bugs when editing in the klampt_browser Python program.
  • Fixed some motion planning bugs (closed loop + moving subset spaces in Python, some planners in C++).
  • Fixed a bizarre Python 2 to 3 conversion bug in se3.mul.

0.8.1 (1/3/2019)

  • Cleaned up documentation, separating C++ and Python docs. Sphinx is now used for Python docs.
  • Added klampt_path utility to Python API.
  • Added Python API bindings for higher order dynamics functions that were already in the C++ library (Cartesian accelerations, Hessians, derivatives of mass matrices).
  • Added rootfind Python C++ extension back.

0.8.0 (12/17/2018)

  • Cleaner file structure, with C++ files in the Cpp directory.
  • Improved build system for Python, allowing easy installation via pip install python.
  • Integration with Jupyter Notebook
  • Added Python utility programs (klampt_browse, klampt_sim, klampt_thumbnail).
  • Improvements support Python visualization on Mac.
  • Upgraded to PyQt5. PyQt4 is still supported for now.
  • Geometry conversions exposed in Python via the convert function.
  • Improved usage of some graphics card resources for streaming point clouds.
  • Support for LOG4CXX logging.
  • Removed dependencies on Boost and upgraded to C++11.
  • Removed dependencies on GLUT and GLUI. (Some examples still need to be upgraded to Qt.)
  • Cleaned up some cruft in KrisLibrary.

0.7 (3/24/2017)

  • Improved simulation stability, including adaptive time stepping and instability detection/recovery.
  • The proprietary .tri geometry file format has been replaced with the Object File Format (OFF) for better compatibility with 3D modeling packages.
  • Simulated visual, depth, and laser range sensors are now fully supported.
  • ROS sensor simulation broadcasting is enabled in Klampt/IO/ROS.h.
  • World XML files can now be saved to disk.
  • Robot sensors and controllers can be attached directly to a robot model using the sensors / controller properties in the robot's .rob or .urdf file.
  • The motion planning structure in KrisLibrary has been completely revamped in preparation for support of optimal and kinodynamic planning, but this should be a mostly transparent change to Klamp't users.
  • The Python interface is now better organized. However, the module structure is incompatible with code developed for versions 0.6.2 and earlier. In particular, math modules (vectorops, so3, se3) are now in the math subpackage, and visualization modules (glprogram, glrobotprogram, etc) are now in the vis subpackage.
  • Custom Python simulations of sensors, actuators, and force appliers that work on fast simulation rates are easier to integrate with slower control loops in the sim.simulation module.
  • Revamped and enhanced Python visualization functionality in the vis module. Multiple windows, simultaneous viewports, trajectory visualization, custom in-visualization plotting, automatic viewport determination, and thumbnail saving are now supported.
  • Cartesian trajectory generation, file loading utilities are added to Python.

0.6.2 (7/31/2016)

  • New Python APIs for visualization
  • Geometry caching helps load times and memory usage for large scenes
  • A global IK solver has been added to the Python API
  • ROS broadcasting / subscribing is enabled in the C++ API.

0.6.1 (3/21/2015)

  • Added functionality in Python API to load/save/edit resources, manipulate transforms and robot configurations via widgets, change appearance of objects, and run programs through Qt.
  • Removed the Python collide module. All prior functionality is now placed in the Geometry3D class in the standard klampt module.
  • Real-time planning interface has been greatly simplified.
  • The MilestonePathController class will be deprecated, use PolynomialPathController instead.
  • Minor bug fixes

0.6 (7/4/2014)

  • CMake build system makes it easier to build across multiple platforms
  • Easy connections with external controllers via ROS or a serial protocol
  • More user-friendly Qt application front ends
  • More demos, example code, and tutorials
  • Direct loading of URDF files with <klampt> XML tag
  • More calibrated robots: Baxter, RobotiQ 3-finger adaptive gripper
  • Unification of locomotion and manipulation via the GeneralizedRobot mechanism
  • Fixed build for Cygwin
  • More sophisticated logging capabilities in SimTest (contacts, commanded/actual/sensed paths)
  • Miscellaneous debugging throughout

0.5. Initial release (11/17/2013)

Who uses Klamp't?

(This is not an exhaustive list; if you are using Klampt and would like to be listed, let us know!)

Comparison to related packages

  • ROS (Robot Operating System) is a middleware system designed for distributed control of physical robots, and Klamp't is designed to be interoperable with it. Various ROS software packages can replicate many of the functions of Klamp't when used together (Gazebo, KDE, Rviz, MoveIt!), but this approach is difficult since these tools are not as tightly integrated as they are in Klamp't. ROS has limited support for legged robots, and is poorly suited for prototyping high-rate feedback control systems. ROS is heavy-weight, has a steep learning curve especially for non-CS students, and is also not completely cross-platform (only Ubuntu is fully supported).
  • OpenRAVE (Robotics and Animation Virtual Environment) is similar to Klamp't and was developed concurrently by a similar group at CMU. OpenRAVE has more sophisticated manipulation planning functionality. Does not support planning for legged robots, but simulation is possible with some effort. Simulation models are often conflated with planning models whereas in Klamp't they are fully decoupled. OpenRAVE is no longer actively supported.
  • Gazebo, Webots, V-REP, etc are robot simulation packages built off of the same class of rigid body simulations as Klamp't. They have more sophisticated sensor simulation capabilities, cleaner APIs, and nicer visualizations but are typically built for mobile robots and have limited functionality for modeling, planning, and optimization. Klamp't also has improved mesh-mesh collision handling that makes collision handling much more stable.

Contributors

Kris Hauser has been the primary maintainer throughout the project. Other major contributors include Zherong Pan, Gao Tang, Jordan Tritell, Jingru Luo, and Alessio Rocchi.

Adam Konnecker, Cam Allen, and Steve Kuznetsov have helped with the Mac build. Hayden Bader helped with the prebuilt Docker container.

As an open-source project, we welcome contributions and suggestions from the community.

klampt's People

Contributors

agarwalsaurav avatar alexanderdsmith avatar aorthey avatar arocchi avatar camall3n avatar cedriclmenard avatar danyresasco avatar dcis101 avatar djzielin avatar ezhang887 avatar hpbader42 avatar iml-shared avatar joaomcm avatar krishauser avatar mass2010chromium avatar mr90x avatar muyimolin avatar neka-nat avatar parsariazi98 avatar patricknaughton01 avatar shaoxiongyao avatar shihaowang avatar smeng9 avatar stevekuznetsov avatar whutddk avatar yifanzhu95 avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

klampt's Issues

Inconsistency in the name of drawextra.h

The file UserInterface.cpp include the GL/drawExtra.h, but the actual file inside GL is drawextra.h. by making them consistent, the compiling error can be fixed

Path -> Trajectory with constraints

Hello!

Super cool library, looks pretty useful.

I am currently working on a classical 3D motion execution problem on a racecar. I.e. I have a pre-prescribed path that I need a racecar to follow, i.e. a list of time-free waypoints in SE3 (although for relatively flat regions of SE3, the SE2 approximation in the plane of the car's axles is pretty good). Technically, these waypoints are parameterized by arclength along the path, but that doesn't help with forming a trajectory.

This racecar is quite zippy, but it's dynamics are (obviously) not instantaneous. Does Klampt have any ready-made code for producing a trajectory from this path that follows the prescribed path(as closely as math will allow) without violating the various dynamic constraints of the car? E.g. don't exceed a provided maximum velocity, linear acceleration, and (most critically) centripetal acceleration.

This problem is nothing super complicated and I could take a stab at rolling my own solution, but if Klampt already has it done, I may as well use a library and avoid the headache and risk that I'll screw it up (which is quite high).

Thanks!
--Trent

Release Binary has no Architecture listed

Downloading the deb binary and trying to install it using dpkg creates the following error:

$ wget http://motion.pratt.duke.edu/software/Klampt-0.6.0-Linux.deb
$ dpkg -i Klampt-0.6.0-Linux.deb 
dpkg: warning: parsing file '/var/lib/dpkg/tmp.ci/control' near line 9 package 'klampt':
 empty value for architecture
dpkg: error processing archive Klampt-0.6.0-Linux.deb (--install):
 package architecture () does not match system (amd64)
Errors were encountered while processing:
 Klampt-0.6.0-Linux.deb

MotionPlan memory leaks

When I run the following code snipplet to do motion planning, there will be a bug 'swig/python detected a memory leak of type 'std::string *', no destructor found.'

I located the problem:

  1. only creating a CSpace, it's ok;
  2. just creating a motion planner (use either configurePlanner or simply planner = MotionPlan(...))without using it will cause the bug

This has been tested on both Klampt 0.8.3 & Klampt 0.8.6, Python3.5

Note: I have already call CSpace.close() and motionplanning.destroy() when planning is done.

Looking forward to your reply!

  space = RigidObjectCSpace(group, collider=WorldCollider(world))
  # set start and goal
  start = space.transformToConfig((start_ori, start_pos))
  goal = space.transformToConfig((goal_ori, goal_pos))

  # check if goal is feasible
  goal_flag = True

  # make planner
  try:
      #planner, args = configurePlanner(space, start, goal, type='auto')
      planner = MotionPlan(space, type="sbl")#, connectionThreshold=0.2, shortcut=1)
      planner.setEndpoints(start, goal)
  except RuntimeError as err:
      print('Oops!!')
      goal_flag = False
....
  planner.close()
  motionplanning.destroy()
  space.close()

Program exits with no reason when getting geometry element!

When I run the following code snipplet, the program will exit.
I located the problem, when calling getElement on a geometry Group.
This has been tested on both Python2/Python3.

from klampt import WorldModel,Geometry3D

def make_table(world,table_height,table_width,table_thick,table_depth):
    table=Geometry3D()
    table.loadFile("./data/objects/cube.off")
    table.transform([table_height,0,0,0,table_width,0,0,0,table_thick],[0,0,-table_thick])
    
    legs=[]
    off=0.1
    for i in range(4):
        x=table_height*off if (i&1)==0 else table_height*(1-off)
        y=table_width*off if(i&2)==0 else table_width*(1-off)
        l=Geometry3D()
        l.loadFile("./data/objects/cube.off")
        l.transform([table_thick,0,0,0,table_thick,0,0,0,table_depth-table_thick],[x,y,-table_depth])
        legs.append(l)
    
    table_geom=Geometry3D()
    table_geom.setGroup()
    for i,elem in enumerate([table]+legs):
        g=Geometry3D(elem)
        table_geom.setElement(i,g)
    table=world.makeTerrain("table")
    table.geometry().set(table_geom)
    table.appearance().setColor(1.,1.,1.)
    return table

if __name__=='__main__':
    world=WorldModel()
    table=make_table(world,5,5,0.1,1.)
    for i in range(table.geometry().numElements()):
        print('Getting %dth geometry element!'%i)
        table.geometry().getElement(0)
    print('Successful!')

path_to_trajectory violates joint limits

Hi,

This is more of a question than an issue. I am planning a trajectory within joint limits and then I use the path_to_trajectory function to resample the trajectory with constant velocity. But in doing this, the resulting trajectory often seems to violate the joint limits. I'm assuming this has something to do with the spline smoothing.

Do you have any suggestions on how to get around this issue? If I just clamp the trajectory at the joint limits, that can also have some peculiar outcomes.

Thanks!

Import error when using klampt.sim.batch.doSim

I am using klampt in Python2.7 and installed it with pip. When using the function klampt.sim.batch.doSim, I get the following import error:

Traceback (most recent call last):
File "Main.py", line 3, in
from Simulator import Simulator
File "/home/joris/klampt/my_code/SimulationTrainer/Simulator.py", line 2, in
from klampt.sim import batch
File "/home/joris/.local/lib/python2.7/site-packages/klampt/sim/batch.py", line 2, in
from ..model import map
ImportError: cannot import name map

Am I missing some additional packages?
Thank you!

mount sub-robots to world frame

Hello!

I've been using v0.8.1 for a while and was avoiding updates to keep my code stable. new members of my team have noted that this version is no longer hosted, and went for v0.8.2. Now that I'm trying this version, as well as the latest 0.8.6, it looks like mounting a sub-robot to the world frame is no longer supported.

Was the ability to mount a sub-robot to the world frame via mount -1 "subrobot.rob" as subrobot an accident previously, or is that functionality no longer supported by design? Definitely recognize that it is roughly the same to use two separate robots in the same worldmodel, but this backdoor did have some benefits for me in ease of getting relative transforms, IK of two robots at the same time, abstraction of my state machine simulation that initially starts with the two robots welded together, etc

Any tips in general of how to handle? Or would you also be open to hosting v0.8.1 again so that my team can continue to install as new members onboard?
image

Thanks,
Jason

Error when installing Klampt using pip

Hi,
I am trying to install the python-api version of Klampt.However on executing the pip command,I got an error OpenSSL.SSL.wantreaderror.This was followed by several messages which said that another exception occured while handling the exception.
Could you tell me how to resolve this.

Custom Controller Config

We are trying to use Klamp't with the Yaskawa SDA10F robot. We get the error I have pasted at the bottom when we run this command and try to simulate a path:
./SimTest ../ROSWorkspace/src/new-balance-mqp-vision/motoman/motoman_sda10f_support/urdf/klamp_model.rob

nbmqp@nbmqp-primary:~/Klampt$ ./SimTest ../ROSWorkspace/src/new-balance-mqp-vision/motoman/motoman_sda10f_support/urdf/klamp_model.rob
Initializing ODE...
RobotWorld::LoadRobot: ../ROSWorkspace/src/new-balance-mqp-vision/motoman/motoman_sda10f_support/urdf/klamp_model.rob
Reading robot file ../ROSWorkspace/src/new-balance-mqp-vision/motoman/motoman_sda10f_support/urdf/klamp_model.rob...
Parsing robot file, 44 links read...
Loaded geometries in time 0.031161s, 20090 total primitive elements
Done loading robot file ../ROSWorkspace/src/new-balance-mqp-vision/motoman/motoman_sda10f_support/urdf/klamp_model.rob.
Creating WorldSimulation
Done.
Simulation initial state: 9188 bytes
BACKEND LOADED
Opened controller on address tcp://localhost:3456
set_q command does not work with the robot's controller
ODESimulator: Robot klamp_model energy 0.117455 exceeds threshold 0.00390225
ODERobot::SetVelocities: Error, Get/SetVelocities don't match
dq = 44 0.020751 -0.158581 0.0538793 1.94496 -0.0238093 -0.0269453 -2.47512 -2.10726 -0.878518 1.48329 -0.464283 -0.0918647 0.202579 0.438487 0 0 0 -13.0805 49.6453 -28.6095 0 13.2494 -53.1345 29.1621 0 2.43664 0.928671 -1.60538 0.552849 -0.136736 -0.297011 -0.763685 0 0 0 -26.0308 312.6 -51.4488 0 25.9675 -311.315 51.2257 0 -81.0413
from GetVelocities = 44 0.020751 -0.158581 0.0538793 1.94496 -0.0238093 -0.0269453 -2.47512 -2.10726 -0.878518 1.48329 -0.464284 -0.0918649 0.202579 0.438488 0 0 0 -13.0805 49.6453 -28.6096 0 13.2495 -53.1345 29.1621 0 2.43664 0.928672 -1.60538 0.552849 -0.136736 -0.297011 -0.763687 0 0 0 -26.0308 312.6 -51.4488 0 25.9676 -311.315 51.2257 0 -81.0413
Error: 0.000172902
did you remember to set the robot's configuration?
Press enter to continue...

Do you have any suggestions for fixing this? Thank you.

Using Klampt for ergonomics studies

How to do ergonomics stuff with Klampt?

I am actually not related to robotics at all, but I would like to do ergonomic studies on digital models of forklifts, which seems very related to the above picture.

module 'Klampt' has no attribute 'simulator'

Hi There
Trying to learn to use Klampt, I was wondering which module does the API 'simulator()' belong to?
According to gl_vis.py it should be Klampt.simulator(), however I am getting the error that it does not exist.

thank

HA

Installation on Linux

Hi,

I installed Klampt with following Klamp't Tutorial: Installation on Linux. I'm getting error when I run python kbdrive.py ../../data/tx90roll.xml .

(base) task@task:~/Klampt/Klampt-examples/Python3/demos$ python kbdrive.py ../../data/tx90roll.xml
*** klampt.vis: using Qt5 as the visualization backend ***
kbdrive.py: This example demonstrates how to drive a robot using keyboard input
RobParser: Reading robot file ../../data/robots/tx90pr2.rob...
RobParser: Invalid robot property servoI on line 27
XmlParser: XmlRobot: error loading from file .
XmlParser: XmlWorld: Unable to load robot tx90pr2
Error opening or parsing world file ../../data/tx90roll.xml
Traceback (most recent call last):
File "kbdrive.py", line 118, in
raise RuntimeError("Unable to load model "+fn)
RuntimeError: Unable to load model ../../data/tx90roll.xml

How Can I fix this?
Thank you.

Displaying geometry of franka emika's panda robot URDF throws segfault

I have tried to load and visualize the robot model with klampt. However I get into a segmentation fault below.

Screenshot from 2021-03-29 21-48-18

I first cloned the git repo of https://github.com/frankaemika/franka_ros
Then I converted panda_arm_hand.urdf.xacro file to urdf in ./franka_description/robots/ using $ xacro --inorder panda_arm_hand.urdf.xacro > panda_arm_hand.urdf in http://wiki.ros.org/urdf/Tutorials/Using%20Xacro%20to%20Clean%20Up%20a%20URDF%20File
Finally I followed the tutorial of https://github.com/krishauser/Klampt/blob/master/Cpp/docs/Tutorials/Import-and-calibrate-urdf.md to add <klampt package_root="../.." use_vis_geom="1" />

However during visualization the Meshing::MergeVertices from KrisLibrary somehow crashes.

I will also attach a minimal example in the zip file.
franka_description.zip
To reproduce the issue we need to extract then run display_urdf in ./robots folder.

CSpace calculation

Hello !

Thank you for this usefull library !

I am working on a project where I need to get the C-Space of my robot (currently 2-DOF and 3-DOF, but the idea is to reach a 6-DOF).

The robot (2-DOF or 3-DOF) is inside an environnement, composed by some geometrics shapes. So, in order to get the motion planning, I want to know first how the C-Space will be calculated.

I do not understand how can I make a code which give me only the CSpace in result. Is it possible ? Or we have to give the C-Space ourselves ?
I do not find the explanations in your Klampt-examples repository.

Thanks a lot in advance,
Hugo

Robot links and objects disappear after klampt.robotsim.SimRobotSensor.kinematicSimulate()

I'm having trouble getting correct RGB camera renders while using the workaround in #44. The visualization also seems to have bugs when kinematicSimulate() is called.

With and without the workaround, the behavior in the camera and vis visualization is different.
Vis: When I use the workaround, parts of the robot disappears, and all the RigidObjects disappear.
Camera sensor image: When I do not use the workaround, the render is wrong. With the workaround, the render is mostly correct, except the background color.

We have two scripts with slightly different setup, and the behavior is different in each (I'm not sure what makes them different, the two scripts are big files). The code to produce the RGB images is similar though, we're using:
self.rgbd_cam = self.sim.controller(0).sensor("rgbd_camera")
self.rgbd_cam.kinematicReset ()
self.rgbd_cam.kinematicSimulate(self.world, 3.0)
self.rgb, self.depth = sensing.camera_to_images (self.rgbd_cam)

Setup 1 screenshots:
Workaround off. Visualization and camera: correct behavior, but kinematicSimulate() is slow. (The objects are not in camera view, I haven't tested with objects in camera view yet.)

Workaround on. Visualization: gripper and objects disappeared. Camera: background should be gray but is black.

Setup 2 screenshots:
Workaround off. Visualization: correct behavior. Camera: there should be objects in camera image, but there aren't.

Workaround on. Visualization: robot links and objects disappeared. Camera: Objects show up. But the background should be gray and it's black.
env_workaroundon_robotlinksandobjectsdisappear_rgbbgblack
I printed robot links appearance.getDraw(), and they are all True, but they aren't displayed correctly.

Any clues?

I can potentially strip down the two files and compare, but that will take some time as they're quite involved scripts. It seems the visualization part could be some graphics rendering bug, with geometries not being rendered, but they are probably there. This is only triggered by kinematicSimulate(), without this call, these things never happen.

Or, is there a better way to get camera images (I can try the simulation stepping way without kinematicSimulate next)? We need RGBD and depth, and the slow mode without the GLUT workaround takes a few seconds and we need a lot faster than that...
Thank you!!

Can't use klampt commands

Hi,
I'm using klampt on Ubuntu, I got this error when I'm running any instruction started with bin, the error bellow was gotten when running bin/SimTest Klampt-examples/data/athlete_fractal_1.xml

bash: bin/SimTest: No such file or directory
How can I use them?

Thank you.

How to access frames of interest after using reduce?

Hi,
What's the recommended way to reference frames of interest (such as end-effector) in a reduced robot?
After using reduce(robot), these frames naturally disappear (since they are usually connected with fixed joints in the original URDF). What's the recommended way to retain this information?

Thanks!

Motion Planning for Articulated Robots Example not working with Klampt Examples

Hello !

This example is not working : http://motion.cs.illinois.edu/software/klampt/latest/pyklampt_docs/Manual-Planning.html#motion-planning-for-articulated-robots

My powershell return this :

RobParser: Reading robot file Klampt-examples/data\robots/tx90pr2.rob...
RobParser:    Parsing robot file, 7 links read...
LoadAssimp: Loaded model with 8458 verts and 16883 tris
LoadAssimp: Loaded model with 3637 verts and 7245 tris
LoadAssimp: Loaded model with 3327 verts and 6650 tris
LoadAssimp: Loaded model with 3447 verts and 6884 tris
LoadAssimp: Loaded model with 6258 verts and 12313 tris
LoadAssimp: Loaded model with 8634 verts and 17308 tris
RobParser: Loaded geometries in time 0.065s, 67283 total primitive elements
RobParser:    Mounting subchain file pr2gripper.rob
RobParser: Reading robot file Klampt-examples/data\robots\pr2gripper.rob...
RobParser:    Parsing robot file, 5 links read...
LoadAssimp: Loaded model with 485 verts and 970 tris
LoadAssimp: Loaded model with 539 verts and 1074 tris
LoadAssimp: Loaded model with 482 verts and 956 tris
LoadAssimp: Loaded model with 617 verts and 1238 tris
LoadAssimp: Loaded model with 482 verts and 956 tris
RobParser: Loaded geometries in time 0.011s, 5194 total primitive elements
RobParser: Done loading robot file Klampt-examples/data\robots\pr2gripper.rob
RobParser: Done loading robot file Klampt-examples/data\robots/tx90pr2.rob
LoadAssimp: Loaded model with 11277 verts and 22300 tris
LoadAssimp: Loaded model with 8 verts and 12 tris
LoadAssimp: Loaded model with 8 verts and 12 tris
LoadAssimp: Loaded model with 8 verts and 12 tris
LoadAssimp: Loaded model with 8 verts and 12 tris
LoadAssimp: Loaded model with 8 verts and 12 tris
LoadAssimp: Loaded model with 8 verts and 12 tris
TriMeshTopology: mesh has 16 triangles with duplicate neighbors!
  Triangle range 10164 to 10755
  May see strange results for some triangle mesh operations
TriMeshTopology: mesh has 32 triangles with duplicate neighbors!
  Triangle range 285 to 866
  May see strange results for some triangle mesh operations
TriMeshTopology: mesh has 32 triangles with duplicate neighbors!
  Triangle range 51 to 748
  May see strange results for some triangle mesh operations
Initialized robot collision data structures in time 0.588
Traceback (most recent call last):
  File ".\MotionPlanningRobotArm.py", line 12, in <module>
    space = robotplanning.makeSpace(world,robot,edgeCheckResolution=0.05)
  File "C:\Users\h.sciascia\AppData\Local\Programs\Python\Python37\lib\site-packages\klampt\plan\robotplanning.py", line 95, in makeSpace
    if dr.type() == 'affine':
  File "C:\Users\h.sciascia\AppData\Local\Programs\Python\Python37\lib\site-packages\klampt\robotsim.py", line 4646, in <lambda>
    __getattr__ = lambda self, name: _swig_getattr(self, RobotModelDriver, name)
  File "C:\Users\h.sciascia\AppData\Local\Programs\Python\Python37\lib\site-packages\klampt\robotsim.py", line 79, in _swig_getattr
    return _swig_getattr_nondynamic(self, class_type, name, 0)
  File "C:\Users\h.sciascia\AppData\Local\Programs\Python\Python37\lib\site-packages\klampt\robotsim.py", line 74, in _swig_getattr_nondynamic
    return object.__getattr__(self, name)
AttributeError: type object 'object' has no attribute '__getattr__'

Python class GLSimulationProgram not found

Hi,

I was trying to run the the gltemplate.py file from the Python/demos directory. However, it gives an error
ImportError: cannot import GLSimulationProgram

I searched for the class GLSimulationProgram but couldn't find it anywhere in the source code. It appears that GLSimulationProgram was changed to GLSimulationPlugin in the commit
d95eac6.

The demo file sphero.py has the same issue.

Regards,
Saurav

P.S. I tried changing GLSimulationProgram ro GLSimulationPlugin in gltemplate.py but it doesn't seem to work directly due to changes in the number of parameters. I shall give a shot at fixing this.

Issues with kinematicSimulate of sensors

IK solver doesn't respect special joint and bad results

Hello,
I tried to create a simple code under python to solve an IK to go from my current pose to a specific point (moved as I want in the simulation)
But I ran into a problem:
Whenever I try to resolve an IK with this rob file:
bras robotse V3 rob.zip
the solver does not respect the special articulations like the affine articulation or the welded articulation (for the connection to the world). like this:
normal:
joint OK

broken:
joint broken

To solve this problem I tried several things and looked all over the python documentation but couldn't find anything. Do you have any idea what might solve this problem?

My second problem is that the solver considers the result OK even if the robot passes through itself.
And this kind of result may give a slight headache:
bad IK

I tried to see with another robot to be sure that it was not my ROB file the problem and I have the same result with the TX90:
bad IK TX90

Similarly, for this problem I looked in the python documentations but I did not see which corresponded to a collision parameter
Do you have any idea to work around this problem?

Thanks.

How to attach link/geometry from different "robot"?

Hi,
I'm populating my world with two "robots" (one manipulator, and one articulated description of the environment). I would like to attach a particular link from the environment (potentially a link connected by a floating joint) to the manipulator. Unfortunately, the setParent(..) method Can't set a link to have a parent on a different robot. How can I achieve my goal?

Thanks!

make apps fails during installation

On ubuntu 18.04:

The make apps step from the installation instructions fails:

 make apps
[ 93%] Built target Klampt
[ 93%] Linking CXX executable ../../bin/TrajOpt
../Dependencies/KrisLibrary/lib/libKrisLibrary.a(fileutils.cpp.o): In function `FileUtils::TempName(char*, char const*, char const*)':
fileutils.cpp:(.text+0x29b): warning: the use of `tempnam' is dangerous, better use `mkstemp'
../../lib/libKlampt.a(TimeScaling.cpp.o): In function `TimeScalingSLP::GetLagrangeMultipliers(std::vector<double, std::allocator<double> >&, std::vector<std::vector<double, std::allocator<double> >, std::allocator<std::vector<double, std::allocator<double> > > >&)':
TimeScaling.cpp:(.text+0x726d): undefined reference to `Optimization::GLPKInterface::GetVariableDual(int)'
TimeScaling.cpp:(.text+0x7293): undefined reference to `Optimization::GLPKInterface::GetVariableDual(int)'
TimeScaling.cpp:(.text+0x72b8): undefined reference to `Optimization::GLPKInterface::GetVariableDual(int)'
TimeScaling.cpp:(.text+0x72e2): undefined reference to `Optimization::GLPKInterface::GetVariableDual(int)'
TimeScaling.cpp:(.text+0x7303): undefined reference to `Optimization::GLPKInterface::GetVariableDual(int)'
../../lib/libKlampt.a(TimeScaling.cpp.o):TimeScaling.cpp:(.text+0x7324): more undefined references to `Optimization::GLPKInterface::GetVariableDual(int)' follow
collect2: error: ld returned 1 exit status
Cpp/Main/CMakeFiles/TrajOpt.dir/build.make:113: recipe for target 'bin/TrajOpt' failed
make[3]: *** [bin/TrajOpt] Error 1
CMakeFiles/Makefile2:319: recipe for target 'Cpp/Main/CMakeFiles/TrajOpt.dir/all' failed
make[2]: *** [Cpp/Main/CMakeFiles/TrajOpt.dir/all] Error 2
CMakeFiles/Makefile2:371: recipe for target 'Cpp/Main/CMakeFiles/apps.dir/rule' failed
make[1]: *** [Cpp/Main/CMakeFiles/apps.dir/rule] Error 2
Makefile:277: recipe for target 'apps' failed
make: *** [apps] Error 2

All the other steps on the installation page work, and the python demos I have run seem to work. I just don't have access to klamp_sim etc.

I also tried updating the docker container to 18.04 as the it fails on the base image of 15.04.

The docker build fails on the make -j deps step with:

/etc/Klampt/Cpp/Dependencies && make -j deps' returned a non-zero code: 2

Tips for tuning Planners parameters

Hi,

Thanks for the great repo! I'm currently trying to apply the prm planner on a 7dof arm planning problem. I'm using PRM since its a multi-query planner (the graph can be re-used for different planning problems). I'm able to get solutions in free space without any obstacles but the PRM struggles (and is very slow) when there is even a single obstacle is added in the environment. Based on reading the docs, I'm just specifying knn:1 in the planner settings. Do you happen to have any tips for tuning PRM?

rrt just worked out of the box, with restart:1 and bidirectional:1.

Some issues and improvement on python bindings

Hi, we are testing the latest Klampt with TRINA project.

Issues:

  • GLEW_DIR seems not detected properly in cmake-gui even after dependencies are updated in ld.so.conf.d
    This will cause import issues in _robotsim module with error "undefined symbol: __glewGenRenderBuffers"
    Update: Issue caused by dependencies KrisLibrary, see pull requests krishauser/KrisLibrary#14

  • Some system does not have "alias python=python3" which may fail python detection in Python/CMakeLists.txt
    Consider changing to IF(PYTHON OR PYTHON2 OR PYTHON3)

Improvements:

  • Update Setup in Cpp/docs/Tutorials/install-Linux.md with apt-install python3-dev for latest python

  • Update FindROS.cmake for latest version of ROS

Thanks

Occasional harmless segfaults on exit in Python with OpenGL visualization

Many OpenGL hardware implementations require display lists to be deleted on the same thread that they are created and used. When a Klampt object with an Appearance is drawn, a display list is created by the vis thread. However, to promote reuse of display list IDs, there's a global display list pool, and display lists do not get deleted when the Appearance is destroyed. Then, when the main program exits, the display list pool attempts to delete the references, and then OpenGL complains and segfaults at glDeleteLists.

Although this doesn't affect any program behavior, the segfault may seem worrying. A potential fix is to comment out the entirety of DisplayListManager::~DisplayListManager() in KrisLibrary/GLDraw/GLDisplayList.cpp, since OpenGL will recover all resources when an OpenGL context is closed. However, this doesn't seem "clean".

Recent Commits to KrisLibrary Broke Installation

When installing Klamp't from source, the following error shows up when compiling KrisLibrary:

/home/yifan/Klampt/Cpp/Dependencies/KrisLibrary/meshing/IO.cpp: In function ‘bool Meshing::LoadAssimp(const char*, std::vector<Meshing::TriMesh>&, std::vector<GLDraw::GeometryAppearance>&)’: /home/yifan/Klampt/Cpp/Dependencies/KrisLibrary/meshing/IO.cpp:1017:15: error: ‘const struct aiScene’ has no member named ‘mMetaData’ if(scene->mMetaData){ ^~~~~~~~~

Checking out KrisLibrary to earlier commits from April fixed the problem.

Release Binaries not on GitHub

It would similarly be useful for people finding this project through GItHub to have the releases hosted on the GitHub "releases" tab.

Difficult to find docs from GitHub

It is difficult to find the documentation if you are discovering this project from the GitHub page. It would be nice to see the documentation (maybe just the basics like this here in README.md and a link to the website for further reading.

make python-install requries sudo

The make python-install requires sudo. This is incompatible with systems that do not have sudo (i.e. Docker containers) and I believe it's accepted as best practice not to call sudo inside make.

$ make python-install
[ 97%] Built target Klampt
[100%] Generating CMakeFiles/python_install_timestamp
/bin/sh: 1: sudo: not found
Python/CMakeFiles/python-install.dir/build.make:51: recipe for target 'Python/CMakeFiles/python_install_timestamp' failed
make[3]: *** [Python/CMakeFiles/python_install_timestamp] Error 127
CMakeFiles/Makefile2:1032: recipe for target 'Python/CMakeFiles/python-install.dir/all' failed
make[2]: *** [Python/CMakeFiles/python-install.dir/all] Error 2
CMakeFiles/Makefile2:1040: recipe for target 'Python/CMakeFiles/python-install.dir/rule' failed
make[1]: *** [Python/CMakeFiles/python-install.dir/rule] Error 2
Makefile:470: recipe for target 'python-install' failed
make: *** [python-install] Error 2

Python3 UI not receving keyboard signals

Zherong: The following code can receive keyboard signals in python2 but not python3:

from klampt.vis import GLProgram,camera,gldraw
from klampt import WorldModel,Geometry3D
import klampt.math.vectorops as op
from klampt.math import se3,so3
import math,klampt

TEXT_COLOR=(0,0,0)

def empty_bb(dim=3):
return ([1000]*dim,[-1000]*dim)

def union_bb(a,b):
if isinstance(b,list):
return union_bb(a,(b,b))
else:
return ([min(c[0],c[1]) for c in zip(a[0],b[0])],
[max(c[0],c[1]) for c in zip(a[1],b[1])])

def expand_bb(bb,expand):
return ([c-expand for c in bb[0]],
[c+expand for c in bb[1]])

def expand_bb_eps(bb,eps):
d=max(op.sub(bb[1],bb[0]))
return expand_bb(bb,d*eps)

def contain_bb(bb,pt):
for d in range(len(bb[0])):
if pt[d]<bb[0][d] or pt[d]>bb[1][d]:
return False
return True

def compute_bb_tight(geom,Rt=None):
if geom.type()=="Group":
return geom.getBB()
#Rtc=geom.getCurrentTransform() if Rt is None else se3.mul(Rt,geom.getCurrentTransform())
#for i in range(geom.numElements()):
# e=geom.getElement(i)
# bb=union_bb(bb,compute_bb_tight(e,Rtc))
#return bb
elif geom.type()=="TriangleMesh":
bb=empty_bb(3)
m=geom.getTriangleMesh()
for v in range(len(m.vertices)//3):
vert=[m.vertices[v*3+d] for d in range(3)]
if Rt is not None:
vert=se3.apply(Rt,vert)
bb=union_bb(bb,vert)
return bb
else:
return None

def get_robot_bb(robot,link0=None):
bb=None
if link0 is None:
link0=0
for i in range(link0,robot.numLinks()):
if i==link0:
bb=compute_bb_tight(robot.link(i).geometry(),robot.link(i).getTransform())
else:
bbI=compute_bb_tight(robot.link(i).geometry(),robot.link(i).getTransform())
if bb is None:
bb=bbI
elif bbI is not None:
bb=union_bb(bb,bbI)
return bb

def get_object_bb(object):
return compute_bb_tight(object.geometry())

class GLVisualizer(GLProgram):
def init(self,world,env=None):
GLProgram.init(self,"Visualizer")
self.path='.'
self.zeroZ=True
self.world=world
self.env=env
self.lockX=False
self.lockY=False
self.frameFunc=None
self.qdq0=None
self.traj=None
self.init_camera()
self.povray_properties={}

def look_at(self,pos,tgt,scale=None):
    if self.lockX:
        tgt[0]=pos[0]
    if self.lockY:
        tgt[1]=pos[1]
    cam=self.view.camera
    if scale is not None:
        cam.dist=op.norm(op.sub(tgt,pos))*scale
    cam.rot=self.get_camera_rot(op.sub(pos,tgt))
    cam.tgt=tgt
    
def get_camera_pos(self):
    cam=self.view.camera
    z=math.sin(-cam.rot[1])
    x=math.sin(cam.rot[2])*math.cos(cam.rot[1])
    y=math.cos(cam.rot[2])*math.cos(cam.rot[1])
    pos=[x,y,z]
    return op.add(cam.tgt,op.mul(pos,cam.dist))

def get_camera_rot(self,d):
    angz=math.atan2(d[0],d[1])
    angy=math.atan2(-d[2],math.sqrt(d[0]*d[0]+d[1]*d[1]))
    return [0,angy,angz]

def get_camera_dir(self,zeroZ=False):
    cam=self.view.camera
    dir=op.sub(cam.tgt,self.get_camera_pos())
    if zeroZ:
        dir=(dir[0],dir[1],0)
    if op.norm(dir)>1e-6:
        dir=op.mul(dir,1/op.norm(dir))
    dir[1]*=-1
    return dir

def get_left_dir(self,zeroZ=False):
    dir=op.cross([0,0,1],self.get_camera_dir())
    if zeroZ:
        dir=(dir[0],dir[1],0)
    if op.norm(dir)>1e-6:
        dir=op.mul(dir,1/op.norm(dir))
    return dir

def init_camera(self):
    bb=empty_bb(3)
    for t in range(self.world.numTerrains()):
        bb=union_bb(bb,self.world.terrain(t).geometry().getBB())
    if self.world.numRobots()>0:
        bb_robot=empty_bb(3)
        for r in range(self.world.numRobots()):
            bb_robot=union_bb(bb_robot,get_robot_bb(self.world.robot(r)))
        bb=union_bb(bb,bb_robot)
    else: bb_robot=bb
    pos=[bb[1][0],(bb[0][1]+bb[1][1])/2,bb_robot[1][2]]
    tgt=[bb[0][0],(bb[0][1]+bb[1][1])/2,bb_robot[0][2]]
    self.look_at(pos,tgt,2.0)
    self.moveSpd=0.005
    self.zoomSpd=1.03
    self.zoomMin=0.01
    self.zoomMax=100.0
    
    self.zoomInCam=False
    self.zoomOutCam=False
    self.forwardCam=False
    self.backCam=False
    self.leftCam=False
    self.rightCam=False
    self.raiseCam=False
    self.sinkCam=False
    return

def keyboardfunc(self,c,x,y):
    if c==b'f':
        self.init_camera()
    elif c==b'z':
        self.zeroZ=not self.zeroZ
    elif c==b'q':
        self.zoomInCam=True
    elif c==b'e':
        self.zoomOutCam=True
    elif c==b'w':
        self.forwardCam=True
    elif c==b's':
        self.backCam=True
    elif c==b'a':
        self.leftCam=True
    elif c==b'd':
        self.rightCam=True
    elif c==b' ':
        self.raiseCam=True
    elif c==b'c':
        self.sinkCam=True
    elif c==b't':
        self.testDerivative=True
    elif c==b'p':
        if self.frameFunc is not None:
            self.povray_properties.update(self.frameFunc(-1))
        povray.render_to_file(self.povray_properties,self.path+"/screenshot.png")
        povray.to_povray(self,self.world,self.povray_properties)
    elif c==b'[':
        #remove existing
        import re,os
        for f in os.listdir(self.path):
            if re.match('[0-9]+.pov',f): 
                os.remove(self.path+"/"+f)
          
        #create new
        cmds=[]
        self.robot=self.world.robot(0)
        for fid in range(self.traj.shape[0]):
            self.robot.setConfig(self.traj[fid,:])
            if self.frameFunc is not None:
                self.povray_properties.update(self.frameFunc(fid))
            povray.render_to_animation(self.povray_properties,self.path)
            cmds.append(povray.to_povray(self,self.world,self.povray_properties))
            
        import pickle
        pickle.dump(cmds,open(self.path+"/cmd.dat",'wb'))
    elif c==b']':
        from povray_animation import render_animation
        render_animation(self.path)
    elif c==b',':
        import pickle
        cam=self.view.camera
        pickle.dump((cam.dist,self.get_camera_pos(),cam.tgt),open(self.path+"/tmpCamera.dat",'wb'))
        print('Saved camera to tmpCamera.dat!')
    elif c==b'.':
        import pickle
        cam=self.view.camera
        cam.dist,pos,tgt=pickle.load(open(self.path+"/tmpCamera.dat",'rb'))
        self.look_at(pos,tgt)
        print('Loaded camera to tmpCamera.dat!')

def keyboardupfunc(self,c,x,y):
    if c==b'q':
        self.zoomInCam=False
    elif c==b'e':
        self.zoomOutCam=False
    elif c==b'w':
        self.forwardCam=False
    elif c==b's':
        self.backCam=False
    elif c==b'a':
        self.leftCam=False
    elif c==b'd':
        self.rightCam=False
    elif c==b' ':
        self.raiseCam=False
    elif c==b'c':
        self.sinkCam=False
    elif c==b't':
        self.testDerivative=False

def display_screen(self):
    gldraw.setcolor(TEXT_COLOR[0],TEXT_COLOR[1],TEXT_COLOR[2])
    
def display(self):
    self.world.drawGL()

def handle_camera(self):
    self.view.clippingplanes=(self.view.clippingplanes[0],self.zoomMax)
    cam=self.view.camera
    moveSpd=self.moveSpd*cam.dist
    if self.zoomInCam:
        cam.dist=max(cam.dist/self.zoomSpd,self.zoomMin)
    elif self.zoomOutCam:
        cam.dist=min(cam.dist*self.zoomSpd,self.zoomMax)
    elif self.forwardCam:
        delta=op.mul(self.get_camera_dir(self.zeroZ),moveSpd)
        self.look_at(op.add(self.get_camera_pos(),delta),op.add(cam.tgt,delta))
    elif self.backCam:
        delta=op.mul(self.get_camera_dir(self.zeroZ),-moveSpd)
        self.look_at(op.add(self.get_camera_pos(),delta),op.add(cam.tgt,delta))
    elif self.leftCam:
        delta=op.mul(self.get_left_dir(self.zeroZ),moveSpd)
        self.look_at(op.add(self.get_camera_pos(),delta),op.add(cam.tgt,delta))
    elif self.rightCam:
        delta=op.mul(self.get_left_dir(self.zeroZ),-moveSpd)
        self.look_at(op.add(self.get_camera_pos(),delta),op.add(cam.tgt,delta))
    elif self.raiseCam:
        delta=(0,0,moveSpd)
        self.look_at(op.add(self.get_camera_pos(),delta),op.add(cam.tgt,delta))
    elif self.sinkCam:
        delta=(0,0,-moveSpd)
        self.look_at(op.add(self.get_camera_pos(),delta),op.add(cam.tgt,delta))

def idle(self):
    self.handle_camera()

if name=='main':
world=klampt.WorldModel()
pt=klampt.GeometricPrimitive()
pt.setSphere([0,0,0],1)
geom=world.makeTerrain('sphere')
geom.geometry().setGeometricPrimitive(pt)
geom.appearance().setColor(1.,0.,0.)

#robot=world.loadRobot("data/Robosimian/robosimian_caesar_new_all_active.urdf")
vis=GLVisualizer(world)
vis.run()

Get an error importing the _robotsim module when calling import klampt

Hello! When I try running the Jupyter examples, an error occured and it reminded me that there's no _robotisim module. So I followed your instructions, using the Dependencies program to open _robotisim.pyd and found that WLDAP32.dll and WS2_32.dll had missing imports.
What should I do next?
Thanks.

possibility for step by step tutorial?

Hello everyone,
I acquired a robotic arm from robotshop a while ago: lynxmotion-al5d-4-degrees-of-freedom-robotic-arm
i already know how to code and control it with arduino but i would like to try something more advanced.

during my search for something evolutive i found this framework and ROS but ROS seems to be very complicated for me.
My point is that I am a beginner in python and have tried the test programs and tried to understand the documentation but I can't seem to put it all into practice ...

Can anyone create a step-by-step tutorial on a "fairly simple" example model like the TX90?
Like how to enter coordinates of a point and find the IK of this point, how to connect 2 points together, how to plan the trajectory, how to set up the simulation, how to link the simulate robot and the real robot ... etc.

maybe I ask a lot but it could help a lot of people in my case who doesn't know how to make a work because they do not know how to do it based only on the documentation and give up

thank you!

Couldn't initialize GLEW (Ubuntu 16.04)

When trying to use a CameraSensor, I get this error:

CameraSensor: Couldn't initialize GLEW, falling back to slow mode
glewInit() error: Missing GL version
This usually happens when an OpenGL context has not been initialized. GL version is: (null)
CameraSensor: GL framebuffers not supported, falling back to slow mode

This has happened on multiple computer systems in Ubuntu 16.04.

Not sure if this is useful, but glewinfo shows that GLEW version 2.0.0 is available on these systems.

The error happens here. Could it be related to this?

Robots with per-face / per-vertex colors act slow using poser

A pretty significant performance issue with the pose editor for robots that have per-face / per-vertex colors. This affects RobotTest, SimTest, and RobotPose, as well as Python code that tries to edit the robot's pose.

Briefly, the poser rebuilds a new display list every time because it copies the appearance, sets a flat color, which clears the openGL display lists. Then to display it, it creates a new display list, but then it destroys the appearance copy.

Possible solutions: store a persistent duplicate appearance/

Regression: Geometry3D groups cannot be displayed properly

After bumping klampt installed from pypi from 0.8.3 to 0.8.5, Geometry3D groups cannot be displayed in visualization. That causes meshes disappearing on TRINA GUI.

I have adapted the examples at the bottom of https://github.com/krishauser/Klampt/blob/master/Python/docs/source/Manual-Modeling.rst into the following zip. The following code cannot display a shelf on 0.8.5, but can display a shelf on 0.8.3. If we display Geometry3D one by one manually, they can still be displayed. However after calling setGroup() it cannot display anything in that group.

geometry3d_regression.zip

Additionally there seems a typo in the provided sample code https://github.com/krishauser/Klampt/blob/master/Python/docs/source/Manual-Modeling.rst w = WorldModel() probably should be changed to world = WorldModel()

mimic Joint not recognized

Hello!

I'm new with this library and i try to migrate from ROS to this, because it seams more adapted to a real time motion planning for teleoperation.

I'm trying to use my robot with this but it have a mimic joint (2 joint rolling on each other and only one is actuated) I managed to create a functional file for ROS but it can't seams to work here.
can we use this kind of joint with this? because I noticed that there was a function that contained this option:

"std::shared_ptr< JointMimic > mimic
Option to Mimic another Joint."

in "urdf_joint.h"

or have I misconfigured my file?
here my URDF
bras_robotise_v3_8.txt

pip version of Klampt 0.8.3 is buggy

Yikes! Squashing bugs now for 0.8.4 bugfix release.

  • klampt_browse is broken due to syntax change in vis.addText
  • multiple resource editing is broken
  • the load/save buttons in resource editing is broken
  • HTML output doesn't save "extras" properly
  • HTML output doesn't close <iframe> tag.

git master branch has all these fixes, but they are not yet available on pip.

How to set the transform of the root link of an element added to the world?

Hi,
I'm trying to set the transformation of the root link of a kinematic chain after loading it into the scene.
No success so far. Last thing I tried:

coordinates.setWorldModel(world)
coordinates.setFrameCoordinates(name='panda:root', coordinates=klampt.math.se3.from_translation([0, 0, 3]))
coordinates.updateToWorld()

What's the recommended way to achieve this?

Thanks!

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.