Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Get configuration values of traj_exec_man #2702

Merged
merged 3 commits into from
Mar 4, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 6 additions & 0 deletions moveit_py/moveit/planning.pyi
Original file line number Diff line number Diff line change
Expand Up @@ -68,6 +68,9 @@ class PlanningSceneMonitor:

class TrajectoryExecutionManager:
def __init__(self, *args, **kwargs) -> None: ...
def allowed_execution_duration_scaling(self, *args, **kwargs) -> Any: ...
def allowed_goal_duration_margin(self, *args, **kwargs) -> Any: ...
def allowed_start_tolerance(self, *args, **kwargs) -> Any: ...
def are_controllers_active(self, *args, **kwargs) -> Any: ...
def clear(self, *args, **kwargs) -> Any: ...
def enable_execution_duration_monitoring(self, *args, **kwargs) -> Any: ...
Expand All @@ -77,6 +80,8 @@ class TrajectoryExecutionManager:
def ensure_active_controllers_for_joints(self, *args, **kwargs) -> Any: ...
def execute(self, *args, **kwargs) -> Any: ...
def execute_and_wait(self, *args, **kwargs) -> Any: ...
def execution_duration_monitoring(self, *args, **kwargs) -> Any: ...
def execution_velocity_scaling(self, *args, **kwargs) -> Any: ...
def get_last_execution_status(self, *args, **kwargs) -> Any: ...
def is_controller_active(self, *args, **kwargs) -> Any: ...
def is_managing_controllers(self, *args, **kwargs) -> Any: ...
Expand All @@ -89,3 +94,4 @@ class TrajectoryExecutionManager:
def set_wait_for_trajectory_completion(self, *args, **kwargs) -> Any: ...
def stop_execution(self, *args, **kwargs) -> Any: ...
def wait_for_execution(self, *args, **kwargs) -> Any: ...
def wait_for_trajectory_completion(self, *args, **kwargs) -> Any: ...
Original file line number Diff line number Diff line change
Expand Up @@ -214,19 +214,37 @@ void initTrajectoryExecutionManager(py::module& m)
If a controller takes longer than expected, the trajectory is canceled.
)")

.def("execution_duration_monitoring",
&trajectory_execution_manager::TrajectoryExecutionManager::executionDurationMonitoring,
R"(
Get the current status of the monitoring of trajectory execution duration.
)")

.def("set_allowed_execution_duration_scaling",
&trajectory_execution_manager::TrajectoryExecutionManager::setAllowedExecutionDurationScaling,
py::arg("scaling"),
R"(
When determining the expected duration of a trajectory, this multiplicative factor is applied to get the allowed duration of execution.
)")

.def("allowed_execution_duration_scaling",
&trajectory_execution_manager::TrajectoryExecutionManager::allowedExecutionDurationScaling,
R"(
Get the current scaling of the duration of a trajectory to get the allowed duration of execution.
)")

.def("set_allowed_goal_duration_margin",
&trajectory_execution_manager::TrajectoryExecutionManager::setAllowedGoalDurationMargin, py::arg("margin"),
R"(
When determining the expected duration of a trajectory, this additional margin s applied after scalign to allow more than the expected execution time before triggering trajectory cancel.
)")

.def("allowed_goal_duration_margin",
&trajectory_execution_manager::TrajectoryExecutionManager::allowedGoalDurationMargin,
R"(
Get the current margin of the duration of a trajectory to get the allowed duration of execution.
)")

.def("set_execution_velocity_scaling",
&trajectory_execution_manager::TrajectoryExecutionManager::setExecutionVelocityScaling, py::arg("scaling"),
R"(
Expand All @@ -235,16 +253,33 @@ void initTrajectoryExecutionManager(py::module& m)
By default, this is 1.0
)")

.def("execution_velocity_scaling",
&trajectory_execution_manager::TrajectoryExecutionManager::executionVelocityScaling,
R"(
Get the current scaling of the execution velocities.
)")

.def("set_allowed_start_tolerance",
&trajectory_execution_manager::TrajectoryExecutionManager::setAllowedStartTolerance, py::arg("tolerance"),
R"(
Set joint-value tolerance for validating trajectory's start point against current robot state.
)")

.def("allowed_start_tolerance", &trajectory_execution_manager::TrajectoryExecutionManager::allowedStartTolerance,
R"(
Get the current joint-value for validating trajectory's start point against current robot state.
)")

.def("set_wait_for_trajectory_completion",
&trajectory_execution_manager::TrajectoryExecutionManager::setWaitForTrajectoryCompletion, py::arg("flag"),
R"(
Enable or disable waiting for trajectory completion.
)")

.def("wait_for_trajectory_completion",
&trajectory_execution_manager::TrajectoryExecutionManager::waitForTrajectoryCompletion,
R"(
Get the current state of waiting for the trajectory being completed.
)");

// ToDo(MatthijsBurgh)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -193,24 +193,42 @@ class MOVEIT_TRAJECTORY_EXECUTION_MANAGER_EXPORT TrajectoryExecutionManager
/// longer than expected, the trajectory is canceled
void enableExecutionDurationMonitoring(bool flag);

/// Get the current status of the monitoring of trajectory execution duration.
bool executionDurationMonitoring() const;

/// When determining the expected duration of a trajectory, this multiplicative factor is applied
/// to get the allowed duration of execution
void setAllowedExecutionDurationScaling(double scaling);

/// Get the current scaling of the duration of a trajectory to get the allowed duration of execution.
double allowedExecutionDurationScaling() const;

/// When determining the expected duration of a trajectory, this multiplicative factor is applied
/// to allow more than the expected execution time before triggering trajectory cancel
void setAllowedGoalDurationMargin(double margin);

/// Get the current margin of the duration of a trajectory to get the allowed duration of execution.
double allowedGoalDurationMargin() const;

/// Before sending a trajectory to a controller, scale the velocities by the factor specified.
/// By default, this is 1.0
void setExecutionVelocityScaling(double scaling);

/// Get the current scaling of the execution velocities.
double executionVelocityScaling() const;

/// Set joint-value tolerance for validating trajectory's start point against current robot state
void setAllowedStartTolerance(double tolerance);

/// Get the current joint-value for validating trajectory's start point against current robot state.
double allowedStartTolerance() const;

/// Enable or disable waiting for trajectory completion
void setWaitForTrajectoryCompletion(bool flag);

/// Get the current state of waiting for the trajectory being completed.
bool waitForTrajectoryCompletion() const;

rclcpp::Node::SharedPtr getControllerManagerNode()
{
return controller_mgr_node_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -255,31 +255,61 @@ void TrajectoryExecutionManager::enableExecutionDurationMonitoring(bool flag)
execution_duration_monitoring_ = flag;
}

bool TrajectoryExecutionManager::executionDurationMonitoring() const
{
return execution_duration_monitoring_;
}

void TrajectoryExecutionManager::setAllowedExecutionDurationScaling(double scaling)
{
allowed_execution_duration_scaling_ = scaling;
}

double TrajectoryExecutionManager::allowedExecutionDurationScaling() const
{
return allowed_execution_duration_scaling_;
}

void TrajectoryExecutionManager::setAllowedGoalDurationMargin(double margin)
{
allowed_goal_duration_margin_ = margin;
}

double TrajectoryExecutionManager::allowedGoalDurationMargin() const
{
return allowed_goal_duration_margin_;
}

void TrajectoryExecutionManager::setExecutionVelocityScaling(double scaling)
{
execution_velocity_scaling_ = scaling;
}

double TrajectoryExecutionManager::executionVelocityScaling() const
{
return execution_velocity_scaling_;
}

void TrajectoryExecutionManager::setAllowedStartTolerance(double tolerance)
{
allowed_start_tolerance_ = tolerance;
}

double TrajectoryExecutionManager::allowedStartTolerance() const
{
return allowed_start_tolerance_;
}

void TrajectoryExecutionManager::setWaitForTrajectoryCompletion(bool flag)
{
wait_for_trajectory_completion_ = flag;
}

bool TrajectoryExecutionManager::waitForTrajectoryCompletion() const
{
return wait_for_trajectory_completion_;
}

bool TrajectoryExecutionManager::isManagingControllers() const
{
return manage_controllers_;
Expand Down
Loading