Tesseract Environment Utility Functions. More...
#include <tesseract_collision/core/utils.h>
#include <iostream>
#include <console_bridge/console.h>
#include <tesseract_environment/utils.h>
#include <tesseract_scene_graph/graph.h>
#include <tesseract_scene_graph/joint.h>
#include <tesseract_state_solver/state_solver.h>
#include <tesseract_kinematics/core/joint_group.h>
#include <tesseract_collision/core/discrete_contact_manager.h>
#include <tesseract_collision/core/continuous_contact_manager.h>
Go to the source code of this file.
Namespaces | |
tesseract_environment | |
Typedefs | |
using | tesseract_environment::CalcStateFn = std::function< tesseract_common::TransformMap(const Eigen::VectorXd &state)> |
Functions | |
bool | tesseract_environment::checkTrajectory (std::vector< tesseract_collision::ContactResultMap > &contacts, tesseract_collision::ContinuousContactManager &manager, const CalcStateFn &state_fn, const std::vector< std::string > &joint_names, const tesseract_common::TrajArray &traj, const tesseract_collision::CollisionCheckConfig &config) |
bool | tesseract_environment::checkTrajectory (std::vector< tesseract_collision::ContactResultMap > &contacts, tesseract_collision::ContinuousContactManager &manager, const tesseract_kinematics::JointGroup &manip, const tesseract_common::TrajArray &traj, const tesseract_collision::CollisionCheckConfig &config) |
Should perform a continuous collision check over the trajectory and stop on first collision. More... | |
bool | tesseract_environment::checkTrajectory (std::vector< tesseract_collision::ContactResultMap > &contacts, tesseract_collision::ContinuousContactManager &manager, const tesseract_scene_graph::StateSolver &state_solver, const std::vector< std::string > &joint_names, const tesseract_common::TrajArray &traj, const tesseract_collision::CollisionCheckConfig &config) |
Should perform a continuous collision check over the trajectory and stop on first collision. More... | |
bool | tesseract_environment::checkTrajectory (std::vector< tesseract_collision::ContactResultMap > &contacts, tesseract_collision::DiscreteContactManager &manager, const CalcStateFn &state_fn, const std::vector< std::string > &joint_names, const tesseract_common::TrajArray &traj, const tesseract_collision::CollisionCheckConfig &config) |
bool | tesseract_environment::checkTrajectory (std::vector< tesseract_collision::ContactResultMap > &contacts, tesseract_collision::DiscreteContactManager &manager, const tesseract_kinematics::JointGroup &manip, const tesseract_common::TrajArray &traj, const tesseract_collision::CollisionCheckConfig &config) |
Should perform a discrete collision check over the trajectory and stop on first collision. More... | |
bool | tesseract_environment::checkTrajectory (std::vector< tesseract_collision::ContactResultMap > &contacts, tesseract_collision::DiscreteContactManager &manager, const tesseract_scene_graph::StateSolver &state_solver, const std::vector< std::string > &joint_names, const tesseract_common::TrajArray &traj, const tesseract_collision::CollisionCheckConfig &config) |
Should perform a discrete collision check over the trajectory and stop on first collision. More... | |
void | tesseract_environment::checkTrajectorySegment (tesseract_collision::ContactResultMap &contact_results, tesseract_collision::ContinuousContactManager &manager, const tesseract_common::TransformMap &state0, const tesseract_common::TransformMap &state1, const tesseract_collision::ContactRequest &contact_request) |
Should perform a continuous collision check between two states only passing along the contact_request to the manager. More... | |
void | tesseract_environment::checkTrajectoryState (tesseract_collision::ContactResultMap &contact_results, tesseract_collision::ContinuousContactManager &manager, const tesseract_common::TransformMap &state, const tesseract_collision::ContactRequest &contact_request) |
Should perform a discrete collision check a state first configuring manager with config. More... | |
void | tesseract_environment::checkTrajectoryState (tesseract_collision::ContactResultMap &contact_results, tesseract_collision::DiscreteContactManager &manager, const tesseract_common::TransformMap &state, const tesseract_collision::ContactRequest &contact_request) |
Should perform a discrete collision check a state only passing contact_request to the manager. More... | |
void | tesseract_environment::getActiveLinkNamesRecursive (std::vector< std::string > &active_links, const tesseract_scene_graph::SceneGraph &scene_graph, const std::string ¤t_link, bool active) |
Get the active Link Names Recursively. More... | |
void | tesseract_environment::printContinuousDebugInfo (const std::vector< std::string > &joint_names, const Eigen::VectorXd &swp0, const Eigen::VectorXd &swp1, tesseract_common::TrajArray::Index step_idx, tesseract_common::TrajArray::Index step_size, tesseract_common::TrajArray::Index sub_step_idx=-1) |
void | tesseract_environment::printDiscreteDebugInfo (const std::vector< std::string > &joint_names, const Eigen::VectorXd &swp, tesseract_common::TrajArray::Index step_idx, tesseract_common::TrajArray::Index step_size, tesseract_common::TrajArray::Index sub_step_idx=-1) |
Tesseract Environment Utility Functions.
Definition in file utils.cpp.