Main Page
Namespaces
Classes
Files
File List
File Members
include
choreo_simulation_execution
simulation_execution_service.h
Go to the documentation of this file.
1
//
2
// Created by yijiangh on 7/12/17.
3
//
4
5
#ifndef CHOREO_PATH_EXECUTION_PATH_EXECUTION_SERVICE_H
6
#define CHOREO_PATH_EXECUTION_PATH_EXECUTION_SERVICE_H
7
8
#include <
ros/ros.h
>
9
#include <choreo_msgs/TrajectoryExecution.h>
10
#include <
actionlib/client/simple_action_client.h
>
11
#include <control_msgs/FollowJointTrajectoryAction.h>
12
13
namespace
choreo_simulation_execution
14
{
15
16
// this class takes "simulation_execution" action from choreo_execution_gatekeeper
17
// and generate "joint_trajectory_action" for simulation
18
// for visualization in Choreo, we use industrial_robot_simulator as action server.
19
20
class
SimulationExecutionService
21
{
22
public
:
23
SimulationExecutionService
(
ros::NodeHandle
& nh);
24
25
bool
executionCallback
(choreo_msgs::TrajectoryExecution::Request& req,
26
choreo_msgs::TrajectoryExecution::Response& res);
27
28
private
:
29
ros::ServiceServer
server_
;
30
actionlib::SimpleActionClient<control_msgs::FollowJointTrajectoryAction>
ac_
;
31
std::string
name_
;
32
};
33
}
34
35
#endif //CHOREO_PATH_EXECUTION_PATH_EXECUTION_SERVICE_H
choreo_simulation_execution
Definition:
simulation_execution_service.h:13
choreo_simulation_execution::SimulationExecutionService::name_
std::string name_
Definition:
simulation_execution_service.h:31
ros::NodeHandle
choreo_simulation_execution::SimulationExecutionService::SimulationExecutionService
SimulationExecutionService(ros::NodeHandle &nh)
Definition:
simulation_execution_service.cpp:19
ros::ServiceServer
actionlib::SimpleActionClient< control_msgs::FollowJointTrajectoryAction >
ros.h
choreo_simulation_execution::SimulationExecutionService
Definition:
simulation_execution_service.h:20
choreo_simulation_execution::SimulationExecutionService::ac_
actionlib::SimpleActionClient< control_msgs::FollowJointTrajectoryAction > ac_
Definition:
simulation_execution_service.h:30
choreo_simulation_execution::SimulationExecutionService::server_
ros::ServiceServer server_
Definition:
simulation_execution_service.h:29
choreo_simulation_execution::SimulationExecutionService::executionCallback
bool executionCallback(choreo_msgs::TrajectoryExecution::Request &req, choreo_msgs::TrajectoryExecution::Response &res)
Definition:
simulation_execution_service.cpp:34
simple_action_client.h
choreo_simulation_executor
Author(s):
autogenerated on Thu Jul 18 2019 03:59:21