Code Monkey home page Code Monkey logo

herbpy's Introduction

HERBPy

Build Status

HerbPy is a Python library for interacting with HERB through OpenRAVE. HERB is a bimanual mobile manipulator designed and built by the [Personal Robotics Lab] (https://personalrobotics.ri.cmu.edu) at [Carnegie Mellon University] (http://www.cmu.edu). HerbPy expands the robot-agnostic helper library [PrPy] (https://github.com/personalrobotics/prpy) by wrapping HERB-specific functionality.

Installation

The following rosinstall can be used to get the minimum dependencies required to use HerbPy in simulation:

$ wstool merge https://raw.githubusercontent.com/personalrobotics/pr-rosinstalls/master/herb-minimal-sim.rosinstall

If you plan to connect to the real robot, then you will need a larger set of dependencies:

$ wstool merge https://raw.githubusercontent.com/personalrobotics/pr-rosinstalls/master/herb-minimal-remote-op.rosinstall

Running HerbPy

You use HerbPy in your script by simply calling the initialize function:

env, robot = herbpy.initialize()

By default, this function loads the OpenRAVE plugins necessary to communicate with HERB's hardware drivers. You can run HerbPy in simulation mode by passing the option sim=True. In both cases, you can optionally attach a viewer to the OpenRAVE environment by passing attach_viewer=True.

See herbpy.herb.initialize for the full list of initialization options.

HerbPy Console

HerbPy includes console.py, a helper script for launching an interactive Python environment. Several common herbpy.herb.initialize options are exposed as command-line arguments:

$ rosrun herbpy console.py
$ rosrun herbpy console.py --sim     # equivalent to sim=True
$ rosrun herbpy console.py --viewer  # equivalent to attach_viewer=True

Using HERBRobot

The robot returned by herbpy.herb.initialize is an OpenRAVE robot of type herbpy.herbrobot.HERBRobot. This object provides access to all of HERB's hardware-specific functionality:

  • robot.left_arm, robot.right_arm : prpy.base.wam.WAM - Barrett WAM arms
  • robot.left_hand, robot.right_hand : prpy.base.barretthand.BarrettHand - BarrettHand end-effectors
  • robot.head : herbpy.herbpantilt.HERBPantilt - custom pan-tilt head
  • robot.base : herbpy.herbbase.HerbBase - Segway RMP mobile base

Basic Arm Usage

We'll default to the right arm (robot.right_arm.SetActive()) in these examples, keep in mind you can do the same things for the left arm too (with robot.left_arm.SetActive()).

The arms can be in two modes, stiff and not stiff. When the arms are not stiff, they are in gravity compensation mode and can be moved around. When the arms are stiff, they cannot be moved, but now planning can be performed.

To make an arm stiff,

robot.right_arm.SetStiffness(1)

And to put it back into gravity compensation mode

robot.right_arm.SetStiffness(0)

Make sure the arms are stiff before you begin planning and executing trajectories!

The state of an arm is given by its configuration, or DOFValues (degrees of freedom) values. You can get these by calling

robot.right_arm.GetDOFValues()

To plan between two configurations of the arm, you can run

robot.right_arm.PlanToConfiguration(config, execute=True)

This will compute a plan and then immediately execute it.

There are also named configurations corresponding to common arm configurations. The two most used are 'relaxed_home' and 'home'. You can plan to one of these by running

robot.PlanToNamedConfiguration('relaxed_home', execute=True)

or for a single arm

robot.right_arm.PlanToNamedConfiguration('relaxed_home', execute=True)

If you do not want to immediately execute a trajectory, you can instead do

traj = robot.right_arm.PlanToConfiguration(config, execute=False)
robot.ExecuteTrajectory(traj)

If you do not pass the execute flag, the planner will default to execute=False. You can also add a timeout parameter (in seconds), like so

robot.right_arm.PlanToConfiguration(config, timeout=30)

If planning or execution fails, the PlanToConfiguration call will throw an exception

try:
    robot.right_arm.PlanToConfiguration(config, timeout=30)
except Exception as e:
    print 'uhoh'
    raise

Planning for the End Effector

The most common thing you'll want to do with the arms is move them such that the hand, or end effector, is at a particular position and orientation (a pose) in the world. To plan to a pose, you must first generate a configuration that corresponds to that pose.

pose_in_world = ... # must be a 4x4 homogeneous transformation matrix
filter_options = openravepy.IkFilterOptions.CheckEnvCollisions # or 0 for no collision checks
config = robot.right_arm.FindIKSolution(pose_in_world, filter_options) # will return None if no config can be found
robot.right_arm.PlanToConfiguration(config, execute=True)

A shortcut for this is

robot.right_arm.PlanToEndEffectorPose(pose_in_world, execute=True)

You can also move the end effector in an offset from its current position. The following will move .1 meters in the z+ direction (up).

distance = .1
direction = [0,0,1]
robot.right_arm.PlanToEndEffectorOffset(direction, distance, execute=True)

Another method moves the end effector in a direction until a force is felt on the arm.

min_distance = 0
max_distance = .1
direction = [1,0,0]
robot.right_arm.MoveUntilTouch(direction, min_distance, max_distance)

Hands

Each of HERB's hands have 3 fingers. You can change how closed/opened these fingers are, and you can change the spread, which moves the fingers around the axis coming out of the palm of the hand. When the spread is 0, two fingers are across from the other finger. When the spread is 2pi, the fingers are on the same side of the hand next to each other. In the middle, the fingers form a tripod shape.

robot.right_arm.hand.MoveHand(spread=0)

Then to close the hand, you do

robot.right_arm.hand.CloseHand()

To open it,

robot.right_arm.hand.OpenHand()

You can grab an object to mark it as connected to the robot. It will be connected to whatever link of the active part robot was touching the object when the method is called.

robot.right_arm.SetActive()
robot.Grab(obj)

And to release an object:

robot.Release(obj)

You can also perform more precise control of the fingers. When a finger is at its 0 position, it is fully opened. At pi, it is fully closed.

For example, to get the hand ready to grasp a cylinder, you could do

robot.right_arm.hand.MoveHand(f1=0, f2=0, f3=0, spread=0)

Then after you move the hand near the cylinder and you're ready to grab it,

robot.right_arm.hand.MoveHand(f1=2, f2=2, f3=2)

Head

To move the head so that its facing forwards, do

robot.head.MoveTo([0,0])

The first entry is rotation about z, the second is rotation about y. For example, to look left and slightly down,

robot.head.MoveTo([math.pi/2, -math.pi/16])

Base

To get the position of herb, do

robot_pose_in_world = robot.GetTransform()

It can be useful to set HERB's position manually, especially in simulation:

robot.SetTransform(desired_robot_pose_in_world)

To drive HERB forward, do:

distanceInMeters = 1
robot.base.Forward(distanceInMeters)

To rotate 90 degres,

robot.base.Rotate(math.pi/2)

You can also plan with the base

robot_pose_in_world = ...
robot.base.PlanToBasePose(robot_pose_in_world)

Other Examples

Comprehensive example of picking up a Fuze drink bottle: graspFuzeBottle.py

HERB will plan a path for the Segway base using SBPL and drive to the table, grasp the object using a simulated push-grasp and lift it off the table.

Push-grasping example: pushAndGraspCup.py

This depends on the randomized_rearrangement_planning package, which will be released soon, and requires OMPL from ros-indigo-ompl.

herbpy's People

Contributors

aaronjoh avatar brianhou avatar cdellin avatar clintliddick avatar es92 avatar garthz avatar gilwoolee avatar jeking04 avatar liz010 avatar mklingen avatar mkoval avatar psigen avatar shushman avatar sjavdani avatar stepelle avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar

Watchers

 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

herbpy's Issues

Cleanup TSR library locking

We should first decided whether we or not to assume the environment will be locked around all calls to tsrlibrary. Then, we need to cleanup the herb tsrlibrary to be consistent with our decision.

enum34 dependency

enum34 needs to be added as a dependency, and we need a rosdep for it.

robot.PlanToNamedConfiguration( 'home', timeout = 0) fails

The expected behavior is that the function runs asynchronously, but instead it now fails with a PlanningError.

Test:

$ rosrun herbpy console.py --sim
In [1]: robot.PlanToNamedConfiguration('home', timeout=0)

Without the timeout parameter, this succeeds. With it, it produces the following error stream.
Note the complaint from [OMPLSimplifier.cpp:109 PlanPath]; is it using the wrong argument?

Error output follows:

openravepy.inversekinematics: GetDefaultIndices, found 3-intersection centered on index 6
[INFO] [openravepy.inversekinematics:inversekinematics.py:449]:GetDefaultIndices: found 3-intersection centered on index 6
openravepy.inversekinematics: GetDefaultIndices, found 3-intersection centered on index 11
[INFO] [openravepy.inversekinematics:inversekinematics.py:449]:GetDefaultIndices: found 3-intersection centered on index 11
openravepy.inversekinematics: GetDefaultIndices, found 3-intersection centered on index 17
[INFO] [openravepy.inversekinematics:inversekinematics.py:449]:GetDefaultIndices: found 3-intersection centered on index 17
openravepy.inversekinematics: GetDefaultIndices, found 3-intersection centered on index 22
[INFO] [openravepy.inversekinematics:inversekinematics.py:449]:GetDefaultIndices: found 3-intersection centered on index 22
openravepy.inversekinematics: GetDefaultIndices, found 3-intersection centered on index 6
[INFO] [openravepy.inversekinematics:inversekinematics.py:449]:GetDefaultIndices: found 3-intersection centered on index 6
openravepy.inversekinematics: GetDefaultIndices, found 3-intersection centered on index 11
[INFO] [openravepy.inversekinematics:inversekinematics.py:449]:GetDefaultIndices: found 3-intersection centered on index 11
openravepy.inversekinematics: GetDefaultIndices, found 3-intersection centered on index 17
[INFO] [openravepy.inversekinematics:inversekinematics.py:449]:GetDefaultIndices: found 3-intersection centered on index 17
openravepy.inversekinematics: GetDefaultIndices, found 3-intersection centered on index 22
[INFO] [openravepy.inversekinematics:inversekinematics.py:449]:GetDefaultIndices: found 3-intersection centered on index 22
/homes/garthz/ln/local/ros-hydro/src/prpy/src/prpy/planning/snap.py:108: FutureWarning: comparison to `None` will result in an elementwise object comparison in the future.
  params.SetGoalConfig(goal)
/homes/garthz/ln/local/ros-hydro/src/prpy/src/prpy/planning/snap.py:109: FutureWarning: comparison to `None` will result in an elementwise object comparison in the future.
  check = params.CheckPathAllConstraints(curr, goal, [], [], 0., Closed)
/homes/garthz/ln/local/ros-hydro/src/prpy/src/prpy/planning/snap.py:125: FutureWarning: comparison to `None` will result in an elementwise object comparison in the future.
  active_indices, False)
/homes/garthz/ln/local/ros-hydro/src/prpy/src/prpy/planning/snap.py:127: FutureWarning: comparison to `None` will result in an elementwise object comparison in the future.
  active_indices, False)
/homes/garthz/ln/local/ros-hydro/src/prpy/src/prpy/planning/snap.py:130: FutureWarning: comparison to `None` will result in an elementwise object comparison in the future.
  traj.Insert(0, waypoints.ravel())
openravepy.inversekinematics: GetDefaultIndices, found 3-intersection centered on index 6
[INFO] [openravepy.inversekinematics:inversekinematics.py:449]:GetDefaultIndices: found 3-intersection centered on index 6
openravepy.inversekinematics: GetDefaultIndices, found 3-intersection centered on index 11
[INFO] [openravepy.inversekinematics:inversekinematics.py:449]:GetDefaultIndices: found 3-intersection centered on index 11
openravepy.inversekinematics: GetDefaultIndices, found 3-intersection centered on index 17
[INFO] [openravepy.inversekinematics:inversekinematics.py:449]:GetDefaultIndices: found 3-intersection centered on index 17
openravepy.inversekinematics: GetDefaultIndices, found 3-intersection centered on index 22
[INFO] [openravepy.inversekinematics:inversekinematics.py:449]:GetDefaultIndices: found 3-intersection centered on index 22
/homes/garthz/ln/local/ros-hydro/src/prpy/src/prpy/base/robot.py:170: FutureWarning: comparison to `None` will result in an elementwise object comparison in the future.
  cloned_env.Cloned(self).SetActiveDOFs(traj_dofs)
openravepy.inversekinematics: GetDefaultIndices, found 3-intersection centered on index 6
[INFO] [openravepy.inversekinematics:inversekinematics.py:449]:GetDefaultIndices: found 3-intersection centered on index 6
openravepy.inversekinematics: GetDefaultIndices, found 3-intersection centered on index 11
[INFO] [openravepy.inversekinematics:inversekinematics.py:449]:GetDefaultIndices: found 3-intersection centered on index 11
openravepy.inversekinematics: GetDefaultIndices, found 3-intersection centered on index 17
[INFO] [openravepy.inversekinematics:inversekinematics.py:449]:GetDefaultIndices: found 3-intersection centered on index 17
openravepy.inversekinematics: GetDefaultIndices, found 3-intersection centered on index 22
[INFO] [openravepy.inversekinematics:inversekinematics.py:449]:GetDefaultIndices: found 3-intersection centered on index 22
[OMPLSimplifier.cpp:109 PlanPath] Time limit must be positive; got 0.000000.---------------------------------------------------------------------------
PlanningError                             Traceback (most recent call last)
/homes/garthz/ln/local/ros-hydro/src/herbpy/scripts/console.py in <module>()
----> 1 robot.PlanToNamedConfiguration('home', timeout=0)

/homes/garthz/ln/local/ros-hydro/src/prpy/src/prpy/base/robot.pyc in wrapper_method(*args, **kw_args)
     94             @functools.wraps(delegate_method)
     95             def wrapper_method(*args, **kw_args):
---> 96                 return self._PlanWrapper(delegate_method, args, kw_args)
     97 
     98             return wrapper_method

/homes/garthz/ln/local/ros-hydro/src/prpy/src/prpy/base/robot.pyc in _PlanWrapper(self, planning_method, args, kw_args)
    338             # Optionally execute the trajectory.

    339             if kw_args.get('execute', True):
--> 340                 result = self.ExecutePath(result, **kw_args)
    341 
    342             return result

/homes/garthz/ln/local/ros-hydro/src/prpy/src/prpy/base/robot.pyc in ExecutePath(self, path, simplify, smooth, defer, timeout, **kwargs)
    197         else:
    198             return do_execute(path, simplify=simplify, smooth=smooth,
--> 199                               timeout=timeout, **kwargs)
    200 
    201     def ExecuteTrajectory(self, traj, defer=False, timeout=None, period=0.01, **kw_args):

/homes/garthz/ln/local/ros-hydro/src/prpy/src/prpy/base/robot.pyc in do_execute(path, simplify, smooth, timeout, **kwargs)
    173                 if simplify:
    174                     path = self.simplifier.ShortcutPath(cloned_robot, path, defer=False,
--> 175                                                         timeout=timeout, **kwargs)
    176 
    177                 retimer = self.smoother if smooth else self.retimer

/homes/garthz/ln/local/ros-hydro/src/prpy/src/prpy/planning/base.pyc in __call__(self, instance, robot, *args, **kw_args)
     81                 return wrap_future(executor.submit(call_planner))
     82             else:
---> 83                 return call_planner()
     84 
     85     def __get__(self, instance, instancetype):

/homes/garthz/ln/local/ros-hydro/src/prpy/src/prpy/planning/base.pyc in call_planner()
     70                 try:
     71                     planner_traj = self.func(instance, cloned_robot,
---> 72                                              *args, **kw_args)
     73                     return CopyTrajectory(planner_traj, env=env)
     74                 finally:

/homes/garthz/ln/local/ros-hydro/src/prpy/src/prpy/planning/ompl.pyc in ShortcutPath(self, robot, path, timeout, **kwargs)
    213                            PlannerStatus.InterruptedWithSolution ]:
    214             raise PlanningError('Simplifier returned with status {0:s}.'.format(
--> 215                                 str(status)))
    216 
    217         return output_path

PlanningError: Simplifier returned with status Failed.

Regenerate Wave Trajectories

With the head disabled, the DOF indices have changed. The Wave trjaectories need to be regenerated with the correct indices, and the test_Wave unit test re-enabled.

PlanToNamedConfiguration('relaxed_home') fails

The current herbpy build apparently cannot run the entry-level tutorial for PlanToNamedConfiguration().

The following fails from the ipython prompt:
robot.PlanToNamedConfiguration('relaxed_home')

invocation:
rosrun herbpy console.py --sim

Workspace packages, all up to date:
comps
herb_description
herbpy
interactive_markers
or_cdchomp
or_interactivemarker
or_ompl
or_urdf
owd
prpy

Tail of extensive error output:

/homes/garthz/ln/local/ros-hydro/src/prpy/src/prpy/planning/retimer.pyc in RetimeTrajectory(self, robot, path, **kw_args)
69
70 # Compute the timing. This happens in-place.

---> 71 status = RetimeTrajectory(output_traj, False, 1., 1., self.algorithm)
72
73 if status not in [ PlannerStatus.HasSolution,

openrave_exception: openrave (Assert): [/usr/include/boost/smart_ptr/shared_ptr.hpp:418] -> T* boost::shared_ptr::operator->() const [with T = OpenRAVE::PlannerBase], expr: px != 0

zip argument #2 must support iteration again

I think this problem is similar to #35
I am using the block_sorting master.
In simulation, I did:

  • distanceInMeters = 1 robot.base.Forward(distanceInMeters)
  • robot.base.rotate(pi/2)
  • robot_pose_in_world = ... robot.base.PlanToBasePose(robot_pose_in_world)

But they all get the similar error, which is "TypeError: zip argument #2 must support iteration"

In [1]: robot.base.Forward(1.0)
[INFO] [prpy.base.robot:robot.py:393]:do_execute: Post-processing path with 2 waypoints.
[WARNING] [prpy.base.robot:robot.py:300]:do_postprocess: Trajectory contains affine DOFs. Any regular DOFs will be ignored.
[INFO] [prpy.base.robot:robot.py:403]:do_execute: Post-processing took 0.107 seconds and produced a path with 2 waypoints and a duration of 2.500 seconds.
---------------------------------------------------------------------------
TypeError                                 Traceback (most recent call last)
/home/shen/Research/catkin_ws/src/herbpy/scripts/console.py in <module>()
----> 1 robot.base.Forward(1.0)

/home/shen/Research/catkin_ws/src/herbpy/src/herbpy/herbbase.pyc in Forward(self, meters, execute, timeout, **kwargs)
     54         """
     55         if self.simulated or not execute:
---> 56             return MobileBase.Forward(self, meters, execute=execute, timeout=timeout,  **kwargs)
     57         else:
     58             with prpy.util.Timer("Drive segway"):

/home/shen/Research/catkin_ws/src/prpy/src/prpy/base/mobilebase.pyc in Forward(self, meters, execute, direction, **kw_args)
     94         path = create_affine_trajectory(self.robot, [ start_pose, goal_pose ])
     95         if execute:
---> 96             return self.robot.ExecutePath(path, **kw_args)
     97         else:
     98             return path

/home/shen/Research/catkin_ws/src/prpy/src/prpy/base/robot.pyc in ExecutePath(self, path, defer, executor, **kwargs)
    418             return wrap_future(executor.submit(do_execute))
    419         elif defer is False:
--> 420             return do_execute()
    421         else:
    422             raise ValueError('Received unexpected value "{:s}" for defer.'.format(str(defer)))

/home/shen/Research/catkin_ws/src/prpy/src/prpy/base/robot.pyc in do_execute()
    405 
    406             with Timer() as timer:
--> 407                 exec_traj = self.ExecuteTrajectory(traj, defer=False, **kwargs)
    408             SetTrajectoryTags(exec_traj, {Tags.EXECUTION_TIME: timer.get_duration()}, append=True)
    409             return exec_traj

/home/shen/Research/catkin_ws/src/herbpy/src/herbpy/herbrobot.pyc in ExecuteTrajectory(self, traj, *args, **kwargs)
    228             manipulator.ClearTrajectoryStatus()
    229 
--> 230         value = super(HERBRobot, self).ExecuteTrajectory(traj, *args, **kwargs)
    231 
    232         for manipulator in active_manipulators:

/home/shen/Research/catkin_ws/src/prpy/src/prpy/base/robot.pyc in ExecuteTrajectory(self, traj, defer, timeout, period, **kwargs)
    460         # Check that the current configuration of the robot matches the
    461         # initial configuration specified by the trajectory.
--> 462         if not util.IsAtTrajectoryStart(self, traj):
    463             raise exceptions.TrajectoryAborted(
    464                 'Trajectory started from different configuration than robot.')

/home/shen/Research/catkin_ws/src/prpy/src/prpy/util.pyc in IsAtTrajectoryStart(robot, trajectory)
    702 
    703     # Check deviation in each DOF, using OpenRAVE's SubtractValue function.
--> 704     dof_infos = zip(dof_indices, traj_values, robot_values, dof_resolutions)
    705     for dof_index, traj_value, robot_value, dof_resolution in dof_infos:
    706         # Look up the Joint and Axis of the DOF from the robot.

TypeError: zip argument #2 must support iteration

Block TSR library's place and place_on should be renamed.

While reviewing for personalrobotics/magi#2, I realized that block tsr library has 'place' and 'place_on' tsrs, and it's 'place_on' serves as 'place' in many other object tsrs. For consistency across tsrs (so that same tsr name can be used for motion planning across multiple objects), 'place' should be changed to something like 'place_at' and 'place_on' should be changed to 'place'.

robot.head.MoveTo( ) fails

Given:

the console was started as follows:

rosrun herbpy console.py --sim

the following command:

robot.head.MoveTo( [0,0] )

fails as follows:

/homes/garthz/ln/local/ros-hydro/src/prpy/src/prpy/base/manipulator.py:81: FutureWarning: comparison to `None` will result in an elementwise object comparison in the future.
  return self.GetRobot().GetDOFValues(self.GetIndices())
/homes/garthz/ln/local/ros-hydro/src/herbpy/src/herbpy/herbpantilt.py:107: FutureWarning: comparison to `None` will result in an elementwise object comparison in the future.
  traj.Insert(0, current_dof_values, config_spec)
---------------------------------------------------------------------------
openrave_exception                        Traceback (most recent call last)
/homes/garthz/ln/local/ros-hydro/src/herbpy/scripts/console.py in <module>()
----> 1 robot.head.MoveTo( [0,0] )

/homes/garthz/ln/local/ros-hydro/src/herbpy/src/herbpy/herbpantilt.pyc in MoveTo(self, target_dof_values, execute, **kw_args)
    110         # Optionally exeucute the trajectory.

    111         if execute:
--> 112             return self.GetRobot().ExecuteTrajectory(traj, **kw_args)
    113         else:
    114             return traj

/homes/garthz/ln/local/ros-hydro/src/prpy/src/prpy/base/robot.pyc in ExecuteTrajectory(self, traj, defer, timeout, period, **kw_args)
    206         needs_base = util.HasAffineDOFs(traj.GetConfigurationSpecification())
    207 
--> 208         self.GetController().SetPath(traj)
    209 
    210         active_manipulators = self.GetTrajectoryManipulators(traj)

openrave_exception: openrave (Assert): [/tmp/buildd/openrave-0.9.1-7-20141006-0124-/src/libopenrave-core/generictrajectory.cpp:214] -> virtual void OpenRAVE::GenericTrajectory::Sample(std::vector<double>&, OpenRAVE::dReal, const OpenRAVE::ConfigurationSpecification&) const, expr: _timeoffset>=0

Note that other non-zero small-magnitude inputs also fail.
Including the viewer doesn't change the result.

PlanToBasePose throws zip-related error

The PlanToBasePose function in the graspfuzeBottle.py example gives the following error:

Traceback (most recent call last):
  File "graspFuzeBottle.py", line 65, in <module>
    robot.base.PlanToBasePose(base_pose)
  File "/home/shushman/catkin_ws/src/prpy/src/prpy/base/mobilebase.py", line 66, in wrapper_method
    return self._BasePlanWrapper(delegate_method, args, kw_args) 
  File "/home/shushman/catkin_ws/src/prpy/src/prpy/base/mobilebase.py", line 164, in _BasePlanWrapper
    return self.robot.ExecutePath(traj, **kw_args)
  File "/home/shushman/catkin_ws/src/prpy/src/prpy/base/robot.py", line 404, in ExecutePath
    return do_execute()
  File "/home/shushman/catkin_ws/src/prpy/src/prpy/base/robot.py", line 391, in do_execute
    exec_traj = self.ExecuteTrajectory(traj, defer=False, **kwargs)
  File "/home/shushman/catkin_ws/src/prpy/src/prpy/base/robot.py", line 446, in ExecuteTrajectory
    if not util.IsAtTrajectoryStart(self, traj):
  File "/home/shushman/catkin_ws/src/prpy/src/prpy/util.py", line 725, in IsAtTrajectoryStart
    dof_infos = zip(dof_indices, traj_values, robot_values, dof_resolutions)
TypeError: zip argument #2 must support iteration
[INFO] [rospy.core:core.py:387]:signal_shutdown: signal_shutdown [atexit]

Something to do with the traj_values parameter?

Switch to the new version of or_urdf that programmatically constructs HERB

The Fuerte version of HerbPy assumes that a .robot.xml exists, which means it was generated from URDF using or_urdf. In Hydro, we are switching to programmatically loading URDF and SRDF files into OpenRAVE. This means that we need to upgrade HerbPy to load the HERB model using the new or_urdf plugin.

Add lift action

Add an action to the action library that enables the robot to lift a grabbed object by temporarily disabling collisions with the object.

This will (hopefully) enable the following list of commands to be smoothly executed from a simple herbpy console:

robot.DetectObjects()
cup = ...
robot.right_arm.Grasp(cup)
robot.right_arm.Lift(cup)
robot.right_arm.PlanToNamedConfiguration('home')

signal_shutdown and core dumped

When I tried to rosrun the console.py on my Ubuntu, VMWare by doing roscore and:

rosrun herbpy console.py --sim –viewer=rviz 
OR rosrun herbpy console.py --sim –viewer 
OR rosrun herbpy console.py --sim –viewer=interactivemarker

Sometimes it works, but sometimes I ended up with 2 kinds of following errors. What I did was wrong?
1.

[ WARN] [1444023961.921101622]: Group 'head_hand' is empty.
[kinbody.cpp:1470 SetDOFValues] dof 4 value is not in limits 0.000000e+00<5.235988e-01
[kinbody.cpp:1470 SetDOFValues] dof 15 value is not in limits 0.000000e+00<5.235988e-01
Traceback (most recent call last):
  File "/home/shen/Research/catkin_ws/src/herbpy/scripts/console.py", line 44, in <module>
    env, robot = herbpy.initialize(**herbpy_args)
  File "/home/shen/Research/catkin_ws/src/herbpy/src/herbpy/herb.py", line 87, in initialize
    prpy.bind_subclass(robot, HERBRobot, **kw_args)
  File "/home/shen/Research/catkin_ws/src/prpy/src/prpy/bind.py", line 366, in bind_subclass
    instance.__init__(*args, **kw_args)
TypeError: __init__() takes exactly 11 arguments (10 given)
[INFO] [rospy.core:core.py:387]:signal_shutdown: signal_shutdown [atexit]
[WARNING] [root:logger.py:71]:initialize_logging: Install termcolor to colorize log messages.
[ WARN] [1444023690.382634257]: Group 'head_hand' is empty.
[kinbody.cpp:1470 SetDOFValues] dof 4 value is not in limits 0.000000e+00<5.235988e-01
[kinbody.cpp:1470 SetDOFValues] dof 15 value is not in limits 0.000000e+00<5.235988e-01
WARNING: QApplication was not created in the main() thread.
[ INFO] [1444023692.147753289]: Stereo is NOT SUPPORTED
[ INFO] [1444023692.148126118]: OpenGl version: 2.1 (GLSL 1.2).
[INFO] [rospy.core:core.py:387]:signal_shutdown: signal_shutdown [atexit]
Segmentation fault (core dumped)

Fix herbpy unit tests

Many have been failing for a long time, but CI wasn't actually running the tests since the files were marked executable and nosetests doesn't run executable files....

Re-initializing within same script not possible due to viewers

@herlant has been saying that when she tries to reinitialize herbpy (i.e herbpy.initialize(...)) within the same script, then qtcoin, or_rviz, and InteractiveMarker all fail. qtcoin and rviz throw the error:

X Error: BadDrawable (invalid Pixmap or Window parameter) 9
 Extension:    139 (RENDER)
 Minor opcode: 4 (RenderCreatePicture)
 Resource id:  0x3e0002f
X Error: BadWindow (invalid Window parameter) 3
 Major opcode: 2 (X_ChangeWindowAttributes)
 Resource id:  0x3e0002f

while InteractiveMarker stops displaying anything.

Possible error in head.MoveTo

I get this error on typing robot.head.MoveTo([x,y]) :

[OWDController.cpp:324 ExecuteORTrajectory] Adding the trajectory to OWD failed with error: Must hold position before calling AddTrajectory

Add check after trajectory execution

in src/herbpy/herbrobot.py ExecuteTrajectory, replace check with code that tests whether any of the FollowJointTrajectory actions failed, i..e. by inspecting the Future returned by the controller client.

initialize crashes if pr_ordata is not installed

I believe this is related to the recent changes to the perception pipeline we merged in.

@Shushman @jeking04 Can you take a look?

Traceback (most recent call last):
  File "/home/mkoval/storage/herb-ws/src/herbpy/scripts/console.py", line 47, in <module>
    env, robot = herbpy.initialize(**herbpy_args)
  File "/home/mkoval/storage/herb-ws/src/herbpy/src/herbpy/herb.py", line 87, in initialize
    prpy.bind_subclass(robot, HERBRobot, **kw_args)
  File "/home/mkoval/storage/herb-ws/src/prpy/src/prpy/bind.py", line 366, in bind_subclass
    instance.__init__(*args, **kw_args)
  File "/home/mkoval/storage/herb-ws/src/herbpy/src/herbpy/herbrobot.py", line 188, in __init__
    'data/objects')
  File "/home/mkoval/storage/herb-ws/src/prpy/src/prpy/util.py", line 680, in FindCatkinResource
    relative_path))
IOError: Loading resource "data/objects" failed.

Hand Flipped Upside-down for block TSR

Now that the hand and FT sensor are mounted correctly (plan to home config works correctly), it seems the TSR is flipped, so the extended finger points down and hits the table.

No rosdep key for or_pushing

What's the correct way to handle installing herbpy now? rosdep installs test dependencies by default, and exits if a key isn't found.

executePath and executeBasePath don't behave the same

ExecutePath and ExecuteBasePath should have the same function, but they don't.

x = robot.GetTransform()
traj = robot.base.PlanToBasePose(x,execute=False)

Now, when we run:

robot.ExecutePath(traj)
it doesn't do anything.

But running:

robot.base.ExecuteBasePath(traj)
makes the robot move to the goal.

Support for ROSbuild in HERBPpy and other packages

Recently the rosbuild manifest file was removed from the herbpy package, however there remains code that applies for rosbuild.

Are we going to gut the packages of all this code?

In my opinion we should create a branch called "rosbuild" or "groovy" which contains the manifest file, and stop maintaining that branch. That way there's a clean, historical copy of all the work that was done. Then in the master branch we can clean out the old code.

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.