NODE manipulation controller
controller for performig the manipulation
In a nutshell, this node implements a very simple service able to communicate with moveit in order to perform a manipulation with the RoboCLuedo hunter manipulator. The robot comes with a set of predefined poses, that the controller can call under request.
This version of the node, except for containing new poses referred to the new model of robot, introduces a very raw implementation of a asynchronous movement, performed using a simple topic.
- Todo:
implement the asynchronous movement using a ROS action instead. Or, at least, introduce a signal.
- Authors
Francesco Ganci
- Version
v1.2
- Todo:
introduce cartesian planning and a clear end effector
- Todo:
the way the node uses moveit is a bit raw … it would deserve a review.
Note
this implementation supports the developer mode: waitkey, print develop.
Defines
-
NODE_NAME
-
LOGSQUARE(str)
-
OUTLABEL
-
TLOG(msg)
-
TWARN(msg)
-
TERR(msg)
-
DEVELOP_MODE
-
DEVELOP_PRINT
-
WTLOG(msg)
-
WTWARN(msg)
-
WTERR(msg)
-
DEVELOP_WAIKEY
-
WAITKEY
-
SS(chr)
-
SSS(el)
-
ARM_PLANNING_GROUP
-
SERVICE_MANIP
-
TOPIC_MANIP_ASYNC
-
POSE_SET_CARTESIAN
-
POSE_HOME
-
POSE_CAM_LEFT
-
POSE_CAM_RIGHT
-
POSE_CAM_BACK
-
POSE_CAM_LOW
-
POSE_CAM_LOW_LEFT
-
POSE_CAM_LOW_BACK
-
POSE_CAM_LOW_RIGHT
-
POSE_HOME_LOW
-
POSE_NAME_HOME
-
POSE_NAME_CAM_LEFT
-
POSE_NAME_CAM_RIGHT
-
POSE_NAME_CAM_BACK
-
POSE_NAME_CAM_LOW
-
POSE_NAME_CAM_LOW_LEFT
-
POSE_NAME_CAM_LOW_BACK
-
POSE_NAME_CAM_LOW_RIGHT
-
POSE_NAME_HOME_LOW
Functions
-
void shut_msg(int sig)
-
int main(int argc, char *argv[])
-
class node_manipulation_controller
implementation of the node
Public Functions
-
inline node_manipulation_controller()
class constructor
the class constructor performs the initialisation of the move group interface, then sets up some parameters, and finally mves the arm in the home position.
When launched, the node first of all puts the robotic manipulator in a known state, which is the home position.
-
inline void spin()
simple spin (wait for shutdown)
-
inline bool cbk_manip(robocluedo_movement_controller_msgs::ManipulatorPosition::Request &req, robocluedo_movement_controller_msgs::ManipulatorPosition::Response &res)
sybchronous manipulation
given a poture, the service sets it and moves the robotic manipulator until it hasn’t achieved that.
- Parameters
req – the posture to be set
res – if the motion planning succeeded or not
-
inline void cbk_manip_async(const robocluedo_movement_controller_msgs::ManipulatorPositionAsync::ConstPtr &req)
async manpulation command (from topic)
- Todo:
implement a progress checking
Note
once activated, there’s no way to stop the motion!
Private Members
-
ros::NodeHandle nh
ROS node handle.
-
std::string planning_group
moveIt group name
-
moveit::planning_interface::MoveGroupInterface mgi
planning interface
-
moveit::planning_interface::MoveGroupInterface::Plan plan
previously generated plan
-
ros::ServiceServer srv_manip
moveit service
-
ros::Subscriber sub_moveit_async
subscriber moveit async
-
bool movement_async_enabled = true
movement async enabled
-
std::mutex mtx
a mutex for controlling the service calling and the async motion request
-
inline node_manipulation_controller()