Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Create simulation handlers #102

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
35 commits
Select commit Hold shift + click to select a range
7f5f14c
Created interface class and put the RPC handlers in robot folder
alexvannobel Jun 9, 2020
8fe70f3
Now the robot functions interface work just like before
alexvannobel Jun 9, 2020
e0d02d3
Added templates and generation for simulated services
alexvannobel Jun 9, 2020
6637d45
Added the simulation services to the driver headers
alexvannobel Jun 9, 2020
892513b
Added newly generated files to repo
alexvannobel Jun 9, 2020
382909f
Added simulation option to the driver so the gazebo package can launc…
alexvannobel Jun 10, 2020
4e44824
Adapt joint_limits files to correctly take prefix option
alexvannobel Jun 10, 2020
0e6cfe6
Change description and control files to support prefix option
alexvannobel Jun 10, 2020
9de4f6c
Change MoveIt config launch and config files to enable prefix option …
alexvannobel Jun 10, 2020
ab82fde
Added xacro usage in SRDF files to be able to prefix joint names
alexvannobel Jun 10, 2020
3c01900
Adjust ompl planning launch and config files to support prefixing joi…
alexvannobel Jun 11, 2020
f22a40d
Remove --inorder from xacro calls since it's default now
alexvannobel Jun 11, 2020
edec94a
Merge branch 'feature/improve-simulation' into feature/adapt-simulati…
alexvannobel Jun 11, 2020
5587eea
Set default gripper in launch files
alexvannobel Jun 11, 2020
d1990b5
Add namespace to launch file parameters passed to driver
alexvannobel Jun 11, 2020
6b86feb
Added class and implementation for simulator
alexvannobel Jun 11, 2020
fd2c4f3
Add stubs and register handlers for Action API
alexvannobel Jun 11, 2020
4e66bc9
Add implementation for default actions and ReacAction/ReadAllActions
alexvannobel Jun 15, 2020
088919e
Added some unit tests for simulator and CreateAction implentation
alexvannobel Jun 15, 2020
f9abad1
Added the case where the prefix could be empty in XACRO
alexvannobel Jun 15, 2020
efcf923
Added prefix support for fake controllers in MoveIt configs
alexvannobel Jun 15, 2020
6f5b45b
Added a missing prefix value for Gen3 and fix the if and unless tags
alexvannobel Jun 15, 2020
19811b5
Add test launch file to launch simulator unit tests
alexvannobel Jun 15, 2020
1d24817
Don't create the gripper Move Group if no gripper on the arm
alexvannobel Jun 15, 2020
e2843c0
Added DeleteAction implementation and tests
alexvannobel Jun 15, 2020
634e36b
Add implementation and tests for UpdateAction
alexvannobel Jun 16, 2020
b7be7b7
Added basic frame for a threaded action executor
alexvannobel Jun 16, 2020
c5d5785
Added publishing for action topic before and after action execution
alexvannobel Jun 16, 2020
798b43c
Added StopAction logic and tests for executing and aborting actions
alexvannobel Jun 16, 2020
45ae121
Added stubs for other RPCs we want to support at first in simulation
alexvannobel Jun 16, 2020
3f33b02
Added implementation for other RPCs worth simulating
alexvannobel Jun 16, 2020
6fd9104
Added some data structure checks and TODOs in executors
alexvannobel Jun 16, 2020
a78256f
Added tests for newly added RPCs
alexvannobel Jun 16, 2020
6a1b08f
Merge branch 'feature/improve-simulation' into feature/create-simulat…
alexvannobel Jun 16, 2020
e490b55
Remove merge artefacts
alexvannobel Jun 17, 2020
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion kortex_driver/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ if(NOT CMAKE_BUILD_TYPE)
endif()

## find catkin and any catkin packages
find_package(catkin REQUIRED COMPONENTS roscpp rospy std_msgs message_generation actionlib control_msgs urdf)
find_package(catkin REQUIRED COMPONENTS roscpp rospy std_msgs message_generation actionlib control_msgs urdf moveit_ros_planning_interface)
find_package(Boost REQUIRED COMPONENTS system)

file(GLOB_RECURSE generated_files RELATIVE ${PROJECT_SOURCE_DIR} "src/generated/robot/*.cpp" "src/generated/simulation/*.cpp")
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,45 +28,45 @@ class ActuatorConfigSimulationServices : public IActuatorConfigServices

virtual bool SetDeviceID(kortex_driver::SetDeviceID::Request &req, kortex_driver::SetDeviceID::Response &res) override;
virtual bool SetApiOptions(kortex_driver::SetApiOptions::Request &req, kortex_driver::SetApiOptions::Response &res) override;
std::function<kortex_driver::GetAxisOffsets::Response&(kortex_driver::GetAxisOffsets::Request&)> GetAxisOffsetsHandler = nullptr;
std::function<kortex_driver::GetAxisOffsets::Response(const kortex_driver::GetAxisOffsets::Request&)> GetAxisOffsetsHandler = nullptr;
virtual bool GetAxisOffsets(kortex_driver::GetAxisOffsets::Request &req, kortex_driver::GetAxisOffsets::Response &res) override;
std::function<kortex_driver::SetAxisOffsets::Response&(kortex_driver::SetAxisOffsets::Request&)> SetAxisOffsetsHandler = nullptr;
std::function<kortex_driver::SetAxisOffsets::Response(const kortex_driver::SetAxisOffsets::Request&)> SetAxisOffsetsHandler = nullptr;
virtual bool SetAxisOffsets(kortex_driver::SetAxisOffsets::Request &req, kortex_driver::SetAxisOffsets::Response &res) override;
std::function<kortex_driver::SetTorqueOffset::Response&(kortex_driver::SetTorqueOffset::Request&)> SetTorqueOffsetHandler = nullptr;
std::function<kortex_driver::SetTorqueOffset::Response(const kortex_driver::SetTorqueOffset::Request&)> SetTorqueOffsetHandler = nullptr;
virtual bool SetTorqueOffset(kortex_driver::SetTorqueOffset::Request &req, kortex_driver::SetTorqueOffset::Response &res) override;
std::function<kortex_driver::ActuatorConfig_GetControlMode::Response&(kortex_driver::ActuatorConfig_GetControlMode::Request&)> ActuatorConfig_GetControlModeHandler = nullptr;
std::function<kortex_driver::ActuatorConfig_GetControlMode::Response(const kortex_driver::ActuatorConfig_GetControlMode::Request&)> ActuatorConfig_GetControlModeHandler = nullptr;
virtual bool ActuatorConfig_GetControlMode(kortex_driver::ActuatorConfig_GetControlMode::Request &req, kortex_driver::ActuatorConfig_GetControlMode::Response &res) override;
std::function<kortex_driver::SetControlMode::Response&(kortex_driver::SetControlMode::Request&)> SetControlModeHandler = nullptr;
std::function<kortex_driver::SetControlMode::Response(const kortex_driver::SetControlMode::Request&)> SetControlModeHandler = nullptr;
virtual bool SetControlMode(kortex_driver::SetControlMode::Request &req, kortex_driver::SetControlMode::Response &res) override;
std::function<kortex_driver::GetActivatedControlLoop::Response&(kortex_driver::GetActivatedControlLoop::Request&)> GetActivatedControlLoopHandler = nullptr;
std::function<kortex_driver::GetActivatedControlLoop::Response(const kortex_driver::GetActivatedControlLoop::Request&)> GetActivatedControlLoopHandler = nullptr;
virtual bool GetActivatedControlLoop(kortex_driver::GetActivatedControlLoop::Request &req, kortex_driver::GetActivatedControlLoop::Response &res) override;
std::function<kortex_driver::SetActivatedControlLoop::Response&(kortex_driver::SetActivatedControlLoop::Request&)> SetActivatedControlLoopHandler = nullptr;
std::function<kortex_driver::SetActivatedControlLoop::Response(const kortex_driver::SetActivatedControlLoop::Request&)> SetActivatedControlLoopHandler = nullptr;
virtual bool SetActivatedControlLoop(kortex_driver::SetActivatedControlLoop::Request &req, kortex_driver::SetActivatedControlLoop::Response &res) override;
std::function<kortex_driver::GetControlLoopParameters::Response&(kortex_driver::GetControlLoopParameters::Request&)> GetControlLoopParametersHandler = nullptr;
std::function<kortex_driver::GetControlLoopParameters::Response(const kortex_driver::GetControlLoopParameters::Request&)> GetControlLoopParametersHandler = nullptr;
virtual bool GetControlLoopParameters(kortex_driver::GetControlLoopParameters::Request &req, kortex_driver::GetControlLoopParameters::Response &res) override;
std::function<kortex_driver::SetControlLoopParameters::Response&(kortex_driver::SetControlLoopParameters::Request&)> SetControlLoopParametersHandler = nullptr;
std::function<kortex_driver::SetControlLoopParameters::Response(const kortex_driver::SetControlLoopParameters::Request&)> SetControlLoopParametersHandler = nullptr;
virtual bool SetControlLoopParameters(kortex_driver::SetControlLoopParameters::Request &req, kortex_driver::SetControlLoopParameters::Response &res) override;
std::function<kortex_driver::SelectCustomData::Response&(kortex_driver::SelectCustomData::Request&)> SelectCustomDataHandler = nullptr;
std::function<kortex_driver::SelectCustomData::Response(const kortex_driver::SelectCustomData::Request&)> SelectCustomDataHandler = nullptr;
virtual bool SelectCustomData(kortex_driver::SelectCustomData::Request &req, kortex_driver::SelectCustomData::Response &res) override;
std::function<kortex_driver::GetSelectedCustomData::Response&(kortex_driver::GetSelectedCustomData::Request&)> GetSelectedCustomDataHandler = nullptr;
std::function<kortex_driver::GetSelectedCustomData::Response(const kortex_driver::GetSelectedCustomData::Request&)> GetSelectedCustomDataHandler = nullptr;
virtual bool GetSelectedCustomData(kortex_driver::GetSelectedCustomData::Request &req, kortex_driver::GetSelectedCustomData::Response &res) override;
std::function<kortex_driver::SetCommandMode::Response&(kortex_driver::SetCommandMode::Request&)> SetCommandModeHandler = nullptr;
std::function<kortex_driver::SetCommandMode::Response(const kortex_driver::SetCommandMode::Request&)> SetCommandModeHandler = nullptr;
virtual bool SetCommandMode(kortex_driver::SetCommandMode::Request &req, kortex_driver::SetCommandMode::Response &res) override;
std::function<kortex_driver::ActuatorConfig_ClearFaults::Response&(kortex_driver::ActuatorConfig_ClearFaults::Request&)> ActuatorConfig_ClearFaultsHandler = nullptr;
std::function<kortex_driver::ActuatorConfig_ClearFaults::Response(const kortex_driver::ActuatorConfig_ClearFaults::Request&)> ActuatorConfig_ClearFaultsHandler = nullptr;
virtual bool ActuatorConfig_ClearFaults(kortex_driver::ActuatorConfig_ClearFaults::Request &req, kortex_driver::ActuatorConfig_ClearFaults::Response &res) override;
std::function<kortex_driver::SetServoing::Response&(kortex_driver::SetServoing::Request&)> SetServoingHandler = nullptr;
std::function<kortex_driver::SetServoing::Response(const kortex_driver::SetServoing::Request&)> SetServoingHandler = nullptr;
virtual bool SetServoing(kortex_driver::SetServoing::Request &req, kortex_driver::SetServoing::Response &res) override;
std::function<kortex_driver::MoveToPosition::Response&(kortex_driver::MoveToPosition::Request&)> MoveToPositionHandler = nullptr;
std::function<kortex_driver::MoveToPosition::Response(const kortex_driver::MoveToPosition::Request&)> MoveToPositionHandler = nullptr;
virtual bool MoveToPosition(kortex_driver::MoveToPosition::Request &req, kortex_driver::MoveToPosition::Response &res) override;
std::function<kortex_driver::GetCommandMode::Response&(kortex_driver::GetCommandMode::Request&)> GetCommandModeHandler = nullptr;
std::function<kortex_driver::GetCommandMode::Response(const kortex_driver::GetCommandMode::Request&)> GetCommandModeHandler = nullptr;
virtual bool GetCommandMode(kortex_driver::GetCommandMode::Request &req, kortex_driver::GetCommandMode::Response &res) override;
std::function<kortex_driver::GetServoing::Response&(kortex_driver::GetServoing::Request&)> GetServoingHandler = nullptr;
std::function<kortex_driver::GetServoing::Response(const kortex_driver::GetServoing::Request&)> GetServoingHandler = nullptr;
virtual bool GetServoing(kortex_driver::GetServoing::Request &req, kortex_driver::GetServoing::Response &res) override;
std::function<kortex_driver::GetTorqueOffset::Response&(kortex_driver::GetTorqueOffset::Request&)> GetTorqueOffsetHandler = nullptr;
std::function<kortex_driver::GetTorqueOffset::Response(const kortex_driver::GetTorqueOffset::Request&)> GetTorqueOffsetHandler = nullptr;
virtual bool GetTorqueOffset(kortex_driver::GetTorqueOffset::Request &req, kortex_driver::GetTorqueOffset::Response &res) override;
std::function<kortex_driver::SetCoggingFeedforwardMode::Response&(kortex_driver::SetCoggingFeedforwardMode::Request&)> SetCoggingFeedforwardModeHandler = nullptr;
std::function<kortex_driver::SetCoggingFeedforwardMode::Response(const kortex_driver::SetCoggingFeedforwardMode::Request&)> SetCoggingFeedforwardModeHandler = nullptr;
virtual bool SetCoggingFeedforwardMode(kortex_driver::SetCoggingFeedforwardMode::Request &req, kortex_driver::SetCoggingFeedforwardMode::Response &res) override;
std::function<kortex_driver::GetCoggingFeedforwardMode::Response&(kortex_driver::GetCoggingFeedforwardMode::Request&)> GetCoggingFeedforwardModeHandler = nullptr;
std::function<kortex_driver::GetCoggingFeedforwardMode::Response(const kortex_driver::GetCoggingFeedforwardMode::Request&)> GetCoggingFeedforwardModeHandler = nullptr;
virtual bool GetCoggingFeedforwardMode(kortex_driver::GetCoggingFeedforwardMode::Request &req, kortex_driver::GetCoggingFeedforwardMode::Response &res) override;

};
Expand Down
Loading