Trouble trying to find ActionType for "execute_trajectory" Action Server
Hello, i'm running ROS Kinetic on Ubuntu 16.04 and working with the Panda robot from Franka Emika.
I'm currently trying to send a command to the robot via Python scripting, i.e Action Client.
I can already send commands to the robot (like stopping it) through the command line, like:
$ rostopic pub -1 /execute_trajectory/cancel actionlib_msgs/GoalID "stamp:
secs: 0
nsecs: 0
id: ''"
And i would like to do the same but with Python, so i tried the following:
import actionlib
import rospy
from actionlib_msgs.msg import GoalID
from franka_control.msg import ErrorRecoveryAction, ErrorRecoveryActionGoal
def stop_robot():
rospy.init_node('panda_STOPP')
client = actionlib.SimpleActionClient('execute_trajectory', GoalID)
client.wait_for_server()
goal = GoalID()
goal.goal_id.stamp.secs = 0
goal.goal_id.stamp.nsecs = 0
goal.goal_id.id = ''
goal.goal = {}
client.send_goal(goal)
if name == '__main__':
stop_robot()
It doesn't work because GoalID is not an action type message. And in order to create the Client we need one Action message. And i find it strange that there is no action message for GoalID because "execute_trajectory" is actually an action server, meaning there should be an action message for it, right? I don't know if understood the concept of Actions wrongly but any help would be welcome!
Thanks!