Class Plan
LUA wrapper for moveit planning environment dependency to tourch.ros
Methods
Plan:getStartStateMsg ([result]) | Create a ros message for the robot state: moveit_msgs/RobotState |
Plan:getTrajectoryMsg ([result]) | Create a ros message for the robot trajectory: moveit_msgs/RobotTrajectory |
Plan:getPlanningTime () | Get the number of seconds |
Plan:convertTrajectoyMsgToTable ([trajectory_msg]) | Convert a ros message: moveit_msgs/RobotTrajectory |
Plan:convertStartStateMsgToTensor ([start_state]) | Convert a ros message: moveit_msgs/RobotState |
Plan:plot (type) | Creates gnu plot for either position, velocity, acceleration and speed depending input |
Methods
- Plan:getStartStateMsg ([result])
-
Create a ros message for the robot state: moveit_msgs/RobotState
Parameters:
- result ros.Message (optional)
Returns:
-
ros.Message
- Plan:getTrajectoryMsg ([result])
-
Create a ros message for the robot trajectory: moveit_msgs/RobotTrajectory
Parameters:
- result ros.Message (optional)
Returns:
-
ros.Message
- Plan:getPlanningTime ()
-
Get the number of seconds
Returns:
-
number
- Plan:convertTrajectoyMsgToTable ([trajectory_msg])
-
Convert a ros message: moveit_msgs/RobotTrajectory
Parameters:
- trajectory_msg ros.Message (optional)
Returns:
-
Positions, Velocities and Labels (name of each joint)
- Plan:convertStartStateMsgToTensor ([start_state])
-
Convert a ros message: moveit_msgs/RobotState
Parameters:
- start_state ros.Message (optional)
Returns:
-
current position, velocity and labels (name of each joint)
- Plan:plot (type)
-
Creates gnu plot for either position, velocity, acceleration and speed depending input
Parameters:
- type int if 1: Positions are plotted, 2: velocities are plotted,3: accelarations are plotted,4: speed is plotted
Returns:
-
bool
is true if the requested type of the plot is know.