mirror of
https://github.com/moveit/moveit_task_constructor.git
synced 2025-11-04 14:49:57 +08:00
extend comment on unintuitive setter
This commit is contained in:
parent
466bd79b73
commit
d224097f3f
@ -92,7 +92,11 @@ public:
|
||||
}
|
||||
void setIKFrame(const std::string& link) { setIKFrame(Eigen::Isometry3d::Identity(), link); }
|
||||
|
||||
/// setters for target pose
|
||||
/** setters for target pose property
|
||||
*
|
||||
* This property should almost always be set in the InterfaceState sent by the child.
|
||||
* If possible, avoid setting it manually.
|
||||
*/
|
||||
void setTargetPose(const geometry_msgs::PoseStamped& pose) { setProperty("target_pose", pose); }
|
||||
void setTargetPose(const Eigen::Isometry3d& pose, const std::string& frame = "");
|
||||
template <typename T>
|
||||
|
||||
Loading…
Reference in New Issue
Block a user