tesseract_robotics.tesseract_command_language

The command language is used to describe a sequence of commands that can be executed by a robot. The command language is used to provide input waypoint sequences to the planner, and receive output trajectories from the planner.

The command language makes heavy use of type erasure. Unfortunately type erasure does not work with Python, so module level utility functions must be used to create and cast instructions and waypoints. Example commands that are frequently used are CartesianWaypointPoly_wrap_CartesianWaypoint, MoveInstructionPoly_wrap_MoveInstruction, InstructionPoly_as_MoveInstructionPoly, and WaypointPoly_as_StateWaypointPoly, howevere there are many more. While these conversions can be done implicitly in C++, they must be done explicitly in Python.

The ProfileDictionary has a similar problem, and must use special accessor functions that are created for each types that is stored in the dictionary. For instance, for OMPLDefaultPlanProfile the accessor function ProfileDictionary_addProfile_OMPLPlanProfile must be used to store the profile in the dictionary. See the planning examples for examples of using the accessors for the profile dictionary, and see the ProfileDictionary_* accessor functions available in each module.

Classes

CartesianWaypoint Class

class tesseract_robotics.tesseract_command_language.CartesianWaypoint(*args)

CartesianWaypointPoly Class

class tesseract_robotics.tesseract_command_language.CartesianWaypointPoly(*args)
clearSeed()

Clear the seed to empty data structures

hasSeed()

Check if it has a seed. If the position or joint names is empty this returns false

Return type:

boolean

Returns:

True if it has a seed, otherwise false

isToleranced()

Returns true if waypoint has tolerances

Return type:

boolean

Returns:

True if waypoint has tolerances

CompositeInstruction Class

class tesseract_robotics.tesseract_command_language.CompositeInstruction(*args)
flatten(*args)

Overload 1:

Flattens a CompositeInstruction into a vector of Instruction

Parameters:
  • composite_instruction – Input composite instruction to be flattened

  • filter – Used to filter only what should be considered. Should return true to include otherwise false

Return type:

std::vector< std::reference_wrapper< tesseract_planning::InstructionPoly >,std::allocator< std::reference_wrapper< tesseract_planning::InstructionPoly > > >

Returns:

A new flattened vector referencing the original instruction elements


Overload 2:

Flattens a CompositeInstruction into a vector of Instruction

Parameters:
  • instruction – Input composite instruction to be flattened

  • filter – Used to filter only what should be considered. Should return true to include otherwise false

Return type:

std::vector< std::reference_wrapper< tesseract_planning::InstructionPoly const >,std::allocator< std::reference_wrapper< tesseract_planning::InstructionPoly const > > >

Returns:

A new flattened vector referencing the original instruction elements

getFirstInstruction(*args)

Overload 1:

Get the first Instruction in a Composite Instruction that is identified by the filter

Parameters:
  • composite_instruction – Composite Instruction to search

  • locate_filter – The filter to indicate if an instruction should be considered

  • process_child_composites – Indicate if child Composite Instructions should be searched

Return type:

InstructionPoly

Returns:

The first Instruction (Const)


Overload 2:

Get the first Instruction in a Composite Instruction that is identified by the filter

Parameters:
  • composite_instruction – Composite Instruction to search

  • locate_filter – The filter to indicate if an instruction should be considered

  • process_child_composites – Indicate if child Composite Instructions should be searched

Return type:

InstructionPoly

Returns:

The first Instruction (Non-Const)

getFirstMoveInstruction(*args)

Overload 1:

Get the first Move Instruction in a Composite Instruction This does not consider the start instruction in child composite instruction

Parameters:

composite_instruction – Composite Instruction to search

Return type:

MoveInstructionPoly

Returns:

The first Move Instruction (Non-Const)


Overload 2:

Get the first Move Instruction in a Composite Instruction This does not consider the start instruction in child composite instruction

Parameters:

composite_instruction – Composite Instruction to search

Return type:

MoveInstructionPoly

Returns:

The first Move Instruction (Const)

getInstructionCount()

Get number of Instruction in a Composite Instruction

Parameters:
  • composite_instruction – The Composite Instruction to process

  • locate_filter – The filter to indicate if an instruction should be considered

  • process_child_composites – Indicate if child Composite Instructions should be searched

Return type:

int

Returns:

The number of Instructions

getLastInstruction(*args)

Overload 1:

Get the last Instruction in a Composite Instruction that is identified by the filter

Parameters:
  • composite_instruction – Composite Instruction to search

  • locate_filter – The filter to indicate if an instruction should be considered

  • process_child_composites – Indicate if child Composite Instructions should be searched

Return type:

InstructionPoly

Returns:

The Last Instruction (Const)


Overload 2:

Get the last Instruction in a Composite Instruction that is identified by the filter

Parameters:
  • composite_instruction – Composite Instruction to search

  • locate_filter – The filter to indicate if an instruction should be considered

  • process_child_composites – Indicate if child Composite Instructions should be searched

Return type:

InstructionPoly

Returns:

The Last Instruction (Non-Const)

getLastMoveInstruction(*args)

Overload 1:

Get the last Move Instruction in a Composite Instruction This does not consider the start instruction in child composite instruction

Parameters:

composite_instruction – Composite Instruction to search

Return type:

MoveInstructionPoly

Returns:

The last Move Instruction (Non-Const)


Overload 2:

Get the last Move Instruction in a Composite Instruction This does not consider the start instruction in child composite instruction

Parameters:

composite_instruction – Composite Instruction to search

Return type:

MoveInstructionPoly

Returns:

The last Move Instruction (Const)

getMoveInstructionCount()

Get number of Move Instruction in a Composite Instruction This does not consider the start instruction in the child composite instruction

Parameters:

composite_instruction – The Composite Instruction to process

Return type:

int

Returns:

The number of Move Instructions

setProfileOverrides(profile_overrides)

Dictionary of profiles that will override named profiles for a specific task

InstructionPoly Class

class tesseract_robotics.tesseract_command_language.InstructionPoly(*args)

JointWaypoint Class

class tesseract_robotics.tesseract_command_language.JointWaypoint(*args)

JointWaypointPoly Class

class tesseract_robotics.tesseract_command_language.JointWaypointPoly(*args)
isToleranced()

Returns true if waypoint has tolerances

Return type:

boolean

Returns:

True if waypoint has tolerances

MoveInstruction Class

class tesseract_robotics.tesseract_command_language.MoveInstruction(*args)

The move instruction is used when defining the results of a motion planning request

This instruction contains two profiles ‘profile’ and ‘path_profile’ which are similar to industrial robots termination type and Motion Options.

  • profile (Termination Type): is used to define a set of costs/constraints associated only with the waypoint

assigned to this instruction
  • path_profile (Motion Options): is used to define a set of costs/constraints associated only with the path taken

to the waypoint assigned to this instruction

MoveInstructionPoly Class

class tesseract_robotics.tesseract_command_language.MoveInstructionPoly(*args)

ProfileDictionary Class

class tesseract_robotics.tesseract_command_language.ProfileDictionary

This class is used to store profiles for motion planning and process planning This is a thread safe class

A ProfileEntry<T> is a std::unordered_map<std::string, std::shared_ptr<const T>>
  • The key is the profile name

  • Where std::shared_ptr<const T> is the profile

The ProfleEntry<T> is also stored in std::unordered_map where the key here is the std::type_index(typeid(T))

Notes: When adding a profile entry the T should be the base class type.

SetAnalogInstruction Class

class tesseract_robotics.tesseract_command_language.SetAnalogInstruction(*args)
getIndex()

Get the analog index

getKey()

Get the analog key

getValue()

Get the analgo value

SetToolInstruction Class

class tesseract_robotics.tesseract_command_language.SetToolInstruction(*args)
getTool()

Get the tool ID

Return type:

int

Returns:

The tool ID

StateWaypoint Class

class tesseract_robotics.tesseract_command_language.StateWaypoint(*args)

StateWaypointPoly Class

class tesseract_robotics.tesseract_command_language.StateWaypointPoly(*args)

TimerInstruction Class

class tesseract_robotics.tesseract_command_language.TimerInstruction(*args)

This instruction indicates that a timer should be started and when the time expires it either sets a digital output high(1) or low(0).

  • DIGITAL_OUTPUT_HIGH : The digital output will be set to high(1) when the timer expires

  • DIGITAL_OUTPUT_LOW : The digital output will be set to low(0) when the timer expires

getTimerIO()

Get the timer IO

Return type:

int

Returns:

The timer IO

getTimerTime()

Get timer time in second

Return type:

float

Returns:

The timer time in second

getTimerType()

Get the timer type

Return type:

int

Returns:

The timer type

setTimerIO(io)

Set the timer IO

Parameters:

io (int) – The timer IO

setTimerTime(time)

Set timer time in second

Parameters:

time (float) – The timer time in second

setTimerType(type)

Set the timer type

Parameters:

type (int) – The timer type

WaitInstruction Class

class tesseract_robotics.tesseract_command_language.WaitInstruction(*args)

This is a wait instruction similar to wait instruction on industrial controllers. The instruction has several modes of operation.

  • TIME : This will wait for a specified number of seconds and then continue

  • DIGITAL_INPUT_HIGH : This will wait for a digital input to go high(1) then continue

  • DIGITAL_INPUT_LOW : This will wait for a digital input to go low(0) then continue

  • DIGITAL_OUTPUT_HIGH : This will wait for a digital output to go high(1) then continue

  • DIGITAL_OUTPUT_LOW : This will wait for a digital output to go low(0) then continue

getWaitIO()

Get the wait IO

Return type:

int

Returns:

The wait IO

getWaitTime()

Get wait time in second

Return type:

float

Returns:

The wait time in second

getWaitType()

Get the wait type

Return type:

int

Returns:

The wait type

setWaitIO(io)

Set the wait IO

Parameters:

io (int) – The wait IO

setWaitTime(time)

Set wait time in second

Parameters:

time (float) – The wait time in second

setWaitType(type)

Set the wait type

Parameters:

type (int) – The wait type

WaypointPoly Class

class tesseract_robotics.tesseract_command_language.WaypointPoly(*args)

flattenFilterFn Class

class tesseract_robotics.tesseract_command_language.flattenFilterFn(fn)

flattenFilterFnBase Class

class tesseract_robotics.tesseract_command_language.flattenFilterFnBase

locateFilterFn Class

class tesseract_robotics.tesseract_command_language.locateFilterFn(fn)

locateFilterFnBase Class

class tesseract_robotics.tesseract_command_language.locateFilterFnBase

Functions

AnyPoly_as_CartesianWaypoint Function

tesseract_robotics.tesseract_command_language.AnyPoly_as_CartesianWaypoint(_self)

AnyPoly_as_CartesianWaypointPoly Function

tesseract_robotics.tesseract_command_language.AnyPoly_as_CartesianWaypointPoly(_self)

AnyPoly_as_CompositeInstruction Function

tesseract_robotics.tesseract_command_language.AnyPoly_as_CompositeInstruction(_self)

AnyPoly_as_JointWaypoint Function

tesseract_robotics.tesseract_command_language.AnyPoly_as_JointWaypoint(_self)

AnyPoly_as_JointWaypointPoly Function

tesseract_robotics.tesseract_command_language.AnyPoly_as_JointWaypointPoly(_self)

AnyPoly_as_MoveInstruction Function

tesseract_robotics.tesseract_command_language.AnyPoly_as_MoveInstruction(_self)

AnyPoly_as_MoveInstructionPoly Function

tesseract_robotics.tesseract_command_language.AnyPoly_as_MoveInstructionPoly(_self)

AnyPoly_as_SetAnalogInstruction Function

tesseract_robotics.tesseract_command_language.AnyPoly_as_SetAnalogInstruction(_self)

AnyPoly_as_SetToolInstruction Function

tesseract_robotics.tesseract_command_language.AnyPoly_as_SetToolInstruction(_self)

AnyPoly_as_StateWaypoint Function

tesseract_robotics.tesseract_command_language.AnyPoly_as_StateWaypoint(_self)

AnyPoly_as_StateWaypointPoly Function

tesseract_robotics.tesseract_command_language.AnyPoly_as_StateWaypointPoly(_self)

AnyPoly_as_TimerInstruction Function

tesseract_robotics.tesseract_command_language.AnyPoly_as_TimerInstruction(_self)

AnyPoly_as_WaitInstruction Function

tesseract_robotics.tesseract_command_language.AnyPoly_as_WaitInstruction(_self)

AnyPoly_is_CartesianWaypoint Function

tesseract_robotics.tesseract_command_language.AnyPoly_is_CartesianWaypoint(_self)

AnyPoly_is_CartesianWaypointPoly Function

tesseract_robotics.tesseract_command_language.AnyPoly_is_CartesianWaypointPoly(_self)

AnyPoly_is_CompositeInstruction Function

tesseract_robotics.tesseract_command_language.AnyPoly_is_CompositeInstruction(_self)

AnyPoly_is_JointWaypoint Function

tesseract_robotics.tesseract_command_language.AnyPoly_is_JointWaypoint(_self)

AnyPoly_is_JointWaypointPoly Function

tesseract_robotics.tesseract_command_language.AnyPoly_is_JointWaypointPoly(_self)

AnyPoly_is_MoveInstruction Function

tesseract_robotics.tesseract_command_language.AnyPoly_is_MoveInstruction(_self)

AnyPoly_is_MoveInstructionPoly Function

tesseract_robotics.tesseract_command_language.AnyPoly_is_MoveInstructionPoly(_self)

AnyPoly_is_SetAnalogInstruction Function

tesseract_robotics.tesseract_command_language.AnyPoly_is_SetAnalogInstruction(_self)

AnyPoly_is_SetToolInstruction Function

tesseract_robotics.tesseract_command_language.AnyPoly_is_SetToolInstruction(_self)

AnyPoly_is_StateWaypoint Function

tesseract_robotics.tesseract_command_language.AnyPoly_is_StateWaypoint(_self)

AnyPoly_is_StateWaypointPoly Function

tesseract_robotics.tesseract_command_language.AnyPoly_is_StateWaypointPoly(_self)

AnyPoly_is_TimerInstruction Function

tesseract_robotics.tesseract_command_language.AnyPoly_is_TimerInstruction(_self)

AnyPoly_is_WaitInstruction Function

tesseract_robotics.tesseract_command_language.AnyPoly_is_WaitInstruction(_self)

AnyPoly_wrap_CartesianWaypoint Function

tesseract_robotics.tesseract_command_language.AnyPoly_wrap_CartesianWaypoint(inner_waypoint)

AnyPoly_wrap_CartesianWaypointPoly Function

tesseract_robotics.tesseract_command_language.AnyPoly_wrap_CartesianWaypointPoly(inner_waypoint)

AnyPoly_wrap_CompositeInstruction Function

tesseract_robotics.tesseract_command_language.AnyPoly_wrap_CompositeInstruction(inner_waypoint)

AnyPoly_wrap_JointWaypoint Function

tesseract_robotics.tesseract_command_language.AnyPoly_wrap_JointWaypoint(inner_waypoint)

AnyPoly_wrap_JointWaypointPoly Function

tesseract_robotics.tesseract_command_language.AnyPoly_wrap_JointWaypointPoly(inner_waypoint)

AnyPoly_wrap_MoveInstruction Function

tesseract_robotics.tesseract_command_language.AnyPoly_wrap_MoveInstruction(inner_waypoint)

AnyPoly_wrap_MoveInstructionPoly Function

tesseract_robotics.tesseract_command_language.AnyPoly_wrap_MoveInstructionPoly(inner_waypoint)

AnyPoly_wrap_SetAnalogInstruction Function

tesseract_robotics.tesseract_command_language.AnyPoly_wrap_SetAnalogInstruction(inner_waypoint)

AnyPoly_wrap_SetToolInstruction Function

tesseract_robotics.tesseract_command_language.AnyPoly_wrap_SetToolInstruction(inner_waypoint)

AnyPoly_wrap_StateWaypoint Function

tesseract_robotics.tesseract_command_language.AnyPoly_wrap_StateWaypoint(inner_waypoint)

AnyPoly_wrap_StateWaypointPoly Function

tesseract_robotics.tesseract_command_language.AnyPoly_wrap_StateWaypointPoly(inner_waypoint)

AnyPoly_wrap_TimerInstruction Function

tesseract_robotics.tesseract_command_language.AnyPoly_wrap_TimerInstruction(inner_waypoint)

AnyPoly_wrap_WaitInstruction Function

tesseract_robotics.tesseract_command_language.AnyPoly_wrap_WaitInstruction(inner_waypoint)

CartesianWaypointPoly_as_WaypointPoly Function

tesseract_robotics.tesseract_command_language.CartesianWaypointPoly_as_WaypointPoly(_self)

CartesianWaypointPoly_wrap_CartesianWaypoint Function

tesseract_robotics.tesseract_command_language.CartesianWaypointPoly_wrap_CartesianWaypoint(inner_waypoint)

InstructionPoly_as_CompositeInstruction Function

tesseract_robotics.tesseract_command_language.InstructionPoly_as_CompositeInstruction(_self)

InstructionPoly_as_MoveInstruction Function

tesseract_robotics.tesseract_command_language.InstructionPoly_as_MoveInstruction(_self)

InstructionPoly_as_MoveInstructionPoly Function

tesseract_robotics.tesseract_command_language.InstructionPoly_as_MoveInstructionPoly(_self)

InstructionPoly_as_SetAnalogInstruction Function

tesseract_robotics.tesseract_command_language.InstructionPoly_as_SetAnalogInstruction(_self)

InstructionPoly_as_SetToolInstruction Function

tesseract_robotics.tesseract_command_language.InstructionPoly_as_SetToolInstruction(_self)

InstructionPoly_as_TimerInstruction Function

tesseract_robotics.tesseract_command_language.InstructionPoly_as_TimerInstruction(_self)

InstructionPoly_as_WaitInstruction Function

tesseract_robotics.tesseract_command_language.InstructionPoly_as_WaitInstruction(_self)

InstructionPoly_wrap_CompositeInstruction Function

tesseract_robotics.tesseract_command_language.InstructionPoly_wrap_CompositeInstruction(inner_waypoint)

InstructionPoly_wrap_MoveInstruction Function

tesseract_robotics.tesseract_command_language.InstructionPoly_wrap_MoveInstruction(inner_waypoint)

InstructionPoly_wrap_SetAnalogInstruction Function

tesseract_robotics.tesseract_command_language.InstructionPoly_wrap_SetAnalogInstruction(inner_waypoint)

InstructionPoly_wrap_SetToolInstruction Function

tesseract_robotics.tesseract_command_language.InstructionPoly_wrap_SetToolInstruction(inner_waypoint)

InstructionPoly_wrap_TimerInstruction Function

tesseract_robotics.tesseract_command_language.InstructionPoly_wrap_TimerInstruction(inner_waypoint)

InstructionPoly_wrap_WaitInstruction Function

tesseract_robotics.tesseract_command_language.InstructionPoly_wrap_WaitInstruction(inner_waypoint)

JointWaypointPoly_as_WaypointPoly Function

tesseract_robotics.tesseract_command_language.JointWaypointPoly_as_WaypointPoly(_self)

JointWaypointPoly_wrap_JointWaypoint Function

tesseract_robotics.tesseract_command_language.JointWaypointPoly_wrap_JointWaypoint(inner_waypoint)

MoveInstructionPoly_as_InstructionPoly Function

tesseract_robotics.tesseract_command_language.MoveInstructionPoly_as_InstructionPoly(_self)

MoveInstructionPoly_wrap_MoveInstruction Function

tesseract_robotics.tesseract_command_language.MoveInstructionPoly_wrap_MoveInstruction(inner_waypoint)

StateWaypointPoly_as_WaypointPoly Function

tesseract_robotics.tesseract_command_language.StateWaypointPoly_as_WaypointPoly(_self)

StateWaypointPoly_wrap_StateWaypoint Function

tesseract_robotics.tesseract_command_language.StateWaypointPoly_wrap_StateWaypoint(inner_waypoint)

WaypointPoly_as_CartesianWaypoint Function

tesseract_robotics.tesseract_command_language.WaypointPoly_as_CartesianWaypoint(_self)

WaypointPoly_as_CartesianWaypointPoly Function

tesseract_robotics.tesseract_command_language.WaypointPoly_as_CartesianWaypointPoly(_self)

WaypointPoly_as_JointWaypoint Function

tesseract_robotics.tesseract_command_language.WaypointPoly_as_JointWaypoint(_self)

WaypointPoly_as_JointWaypointPoly Function

tesseract_robotics.tesseract_command_language.WaypointPoly_as_JointWaypointPoly(_self)

WaypointPoly_as_StateWaypoint Function

tesseract_robotics.tesseract_command_language.WaypointPoly_as_StateWaypoint(_self)

WaypointPoly_as_StateWaypointPoly Function

tesseract_robotics.tesseract_command_language.WaypointPoly_as_StateWaypointPoly(_self)

WaypointPoly_wrap_CartesianWaypoint Function

tesseract_robotics.tesseract_command_language.WaypointPoly_wrap_CartesianWaypoint(inner_waypoint)

WaypointPoly_wrap_JointWaypoint Function

tesseract_robotics.tesseract_command_language.WaypointPoly_wrap_JointWaypoint(inner_waypoint)

WaypointPoly_wrap_StateWaypoint Function

tesseract_robotics.tesseract_command_language.WaypointPoly_wrap_StateWaypoint(inner_waypoint)

checkJointPositionFormat Function

tesseract_robotics.tesseract_command_language.checkJointPositionFormat(joint_names, waypoint)

Check the waypoints joint order against the provided joint names

Throws if waypoint does not directly contain that information

Also this is an expensive call so the motion planners do not leverage this and they expect the order through out the program all match.

Parameters:
  • joint_names (std::vector< std::string,std::allocator< std::string > >) – The joint names defining the order desired

  • waypoint (WaypointPoly) – The waypoint to check format

Return type:

boolean

Returns:

True if waypoint format is correct, otherwise false.

clampToJointLimits Function

tesseract_robotics.tesseract_command_language.clampToJointLimits(wp, limits, max_deviation)

Clamps a waypoint to be within joint limits

Parameters:
  • wp (WaypointPoly) – Waypoint to be adjusted. Does nothing if not a JointPosition or State waypoint

  • limits (Eigen::Ref< Eigen::MatrixX2d const >) – Matrix2d of limits with first column being lower limits and second column being upper limits

:param max_deviation:. Max deviation that will be clamped

Return type:

boolean

Returns:

True if successful or if the waypoint doesn’t contain that information.

Clamps a waypoint to be within joint limits

Parameters:
  • wp (WaypointPoly) – Waypoint to be adjusted. Does nothing if not a JointPosition or State waypoint

  • limits (Eigen::Ref< Eigen::MatrixX2d const >) – Matrix2d of limits with first column being lower limits and second column being upper limits

:param max_deviation:. Max deviation that will be clamped :rtype: boolean :return: True if successful or if the waypoint doesn’t contain that information.

formatJointPosition Function

tesseract_robotics.tesseract_command_language.formatJointPosition(joint_names, waypoint)

Format the waypoints joint ordered by the provided joint names

Throws if waypoint does not directly contain that information

Also this is an expensive call so the motion planners do not leverage this and they expect the order through out the program all match.

Parameters:
  • joint_names (std::vector< std::string,std::allocator< std::string > >) – The joint names defining the order desired

  • waypoint (WaypointPoly) – The waypoint to format

Return type:

boolean

Returns:

True if formatting was required, otherwise false.

getJointNames Function

tesseract_robotics.tesseract_command_language.getJointNames(waypoint)

Gets joint names from waypoints that contain that information.

Throws if waypoint does not directly contain that information

Parameters:

waypoint (WaypointPoly) – The waypoint to try and extract the joint position from

Return type:

std::vector< std::string,std::allocator< std::string > >

Returns:

The joint names

getJointPosition Function

tesseract_robotics.tesseract_command_language.getJointPosition(*args)

Overload 1:

Gets joint position from waypoints that contain that information.

Throws if waypoint does not directly contain that information

Parameters:

waypoint (WaypointPoly) – The waypoint to try and extract the joint position from

Return type:

Eigen::VectorXd

Returns:

The joint values


Overload 2:

Get the joint positions ordered by the provided joint names

Throws if waypoint does not directly contain that information

Also this is an expensive call so the motion planners do not leverage this and they expect the order through out the program all match.

Parameters:
  • joint_names (std::vector< std::string,std::allocator< std::string > >) – The joint names defining the order desired

  • waypoint (WaypointPoly) – The waypoint to

Return type:

Eigen::VectorXd

Returns:

The joint values ordered by the provided joint_names

isSetAnalogInstruction Function

tesseract_robotics.tesseract_command_language.isSetAnalogInstruction(instruction)

isSetToolInstruction Function

tesseract_robotics.tesseract_command_language.isSetToolInstruction(instruction)

isTimerInstruction Function

tesseract_robotics.tesseract_command_language.isTimerInstruction(instruction)

isWaitInstruction Function

tesseract_robotics.tesseract_command_language.isWaitInstruction(instruction)

isWithinJointLimits Function

tesseract_robotics.tesseract_command_language.isWithinJointLimits(wp, limits)

Checks if a waypoint is

Parameters:
  • wp (WaypointPoly) – Waypoint to be checked. Only checks if a JointPosition or State waypoint (otherwise returns true)

  • limits (Eigen::Ref< Eigen::MatrixX2d const >) – Matrix2d of limits with first column being lower limits and second column being upper limits

Return type:

boolean

Returns:

True if the waypoit falls within the joint limits

setJointPosition Function

tesseract_robotics.tesseract_command_language.setJointPosition(waypoint, position)

Set the joint position for waypoints that contain that information

Parameters:
  • waypoint (WaypointPoly) – Waypoint to set

  • position (Eigen::Ref< Eigen::VectorXd const >) – Joint position

Return type:

boolean

Returns:

true if successful (if the waypoint is a supported type)

toDelimitedFile Function

tesseract_robotics.tesseract_command_language.toDelimitedFile(*args)

Convert a CompositeInstruction to delimited formate file by extracting all MoveInstructions

Parameters:
  • composite_instructions (CompositeInstruction) – The CompositeInstruction to extract data from

  • file_path (string) – The location to save the file

  • separator (char, optional) – The separator to use

Return type:

boolean

Returns:

true if successful

toJointTrajectory Function

tesseract_robotics.tesseract_command_language.toJointTrajectory(*args)

Overload 1:

Convert instruction to a joint trajectory This searches for both move instructions. If it contains a Cartesian waypoint it is skipped.

Parameters:

instruction (InstructionPoly) – The instruction to convert

Return type:

JointTrajectory

Returns:

A joint trajectory


Overload 2:

Convert composite instruction to a joint trajectory This searches for both move and plan instruction to support converting both input and results to planning requests. If it contains a Cartesian waypoint it is skipped.

Parameters:

composite_instructions (CompositeInstruction) – The composite instruction to convert

Return type:

JointTrajectory

Returns:

A joint trajectory

Constants

  • CompositeInstructionOrder_ORDERED

  • CompositeInstructionOrder_ORDERED_AND_REVERABLE

  • CompositeInstructionOrder_UNORDERED

  • DEFAULT_PROFILE_KEY

  • MoveInstructionType_CIRCULAR

  • MoveInstructionType_FREESPACE

  • MoveInstructionType_LINEAR

  • TimerInstructionType_DIGITAL_OUTPUT_HIGH

  • TimerInstructionType_DIGITAL_OUTPUT_LOW

  • WaitInstructionType_DIGITAL_INPUT_HIGH

  • WaitInstructionType_DIGITAL_INPUT_LOW

  • WaitInstructionType_DIGITAL_OUTPUT_HIGH

  • WaitInstructionType_DIGITAL_OUTPUT_LOW

  • WaitInstructionType_TIME

Container Templates

  • Instructions -> std::vector<tesseract_planning::InstructionPoly>

  • MoveInstructionPolyVector -> std::vector<tesseract_planning::MoveInstructionPoly>

  • Waypoints -> std::vector<tesseract_planning::WaypointPoly>