The ros package moveit_jog_arm
is now named moveit_servo
. If you were previously using moveit_jog_arm
you will need to do a find/replace for these phrases in your code base:
- jog_arm -> servo
- JogArm -> Servo
- jog_server -> servo_server
The api for moveit_servo
has also recently changed. The short of it is you now use it through ros instead of with method calls. Internally it is now using ros timers instead of threads. This means that you'll need to be using ros::AsyncSpinner
with multiple threads. We recommend you use at least 4 threads.
When servo
is constructed it loads parameters from rosparam. These parameters are loaded into a struct
and after servo is constructed you can access that struct using the Servo::getParameters()
method.
Before you had to provide a thread to start. Now you just call the method Servo::start()
. To stop you call the method Servo::stop()
. This starts/stops ros timers.
Instead of calling methods on the servo object you send commands to it through a ros publisher. To do that you need to setup the publisher for the type of message you are sending and the topic. The topic that moveit_servo
listens to is set in the parameters. Here is how you would connect to the twist stamped command topic:
twist_stamped_pub_ =
nh_.advertise<geometry_msgs::TwistStamped>(servo_->getParameters().cartesian_command_in_topic, 1);
To take advantage of zero copy message passing and memory pool allocations there is a new method in jog arm you can use to allocate each message you send. To use it you'll need to include moveit_servo/make_shared_from_pool.h
.
auto msg = moveit::util::make_shared_from_pool<geometry_msgs::TwistStamped>();
This is now a service and the way you ineteract with it is through ros:
change_drift_dimensions_client_ = nh_.serviceClient<moveit_msgs::ChangeDriftDimensions>(
nh_.getNamespace() + "/" + ros::this_node::getName() + "/change_drift_dimensions");
...
moveit_msgs::ChangeDriftDimensions srv;
srv.request = drift_dimensions;
if (!change_drift_dimensions_client_.call(srv))
{
ROS_ERROR_STREAM_NAMED(LOGNAME, "Failed call to service change_drift_dimensions");
return false;
}
Mention if this is optional or not:
To take advantage of zero copy message passing and memory pool allocations there is a new method in jog arm you can use to allocate each message you send. To use it you'll need to include moveit_servo/make_shared_from_pool.h.