feat(les4): Add basic rviz robot arm
This commit is contained in:
71
.fish/README.md
Normal file
71
.fish/README.md
Normal file
@@ -0,0 +1,71 @@
|
||||
# Exported Fish Environment: ros2-lectures
|
||||
|
||||
This directory contains a self-contained Fish shell environment that can be used
|
||||
without requiring the original Fish configuration.
|
||||
|
||||
## Files Structure
|
||||
```
|
||||
.fish/
|
||||
├── activate.fish # Main environment configuration
|
||||
└── README.md # This file
|
||||
```
|
||||
|
||||
## Usage
|
||||
|
||||
### Automatic Activation (Recommended)
|
||||
The environment will automatically activate when you `cd` into this directory
|
||||
if your Fish shell is configured with the auto-activation feature that checks
|
||||
for `.fish/activate.fish`.
|
||||
|
||||
### Manual Activation
|
||||
To manually activate the environment, run from the project root:
|
||||
```bash
|
||||
source ./.fish/activate.fish
|
||||
```
|
||||
|
||||
### Deactivation
|
||||
To deactivate the environment, run:
|
||||
```bash
|
||||
env deactivate
|
||||
```
|
||||
|
||||
Or simply `cd` to a different directory if using auto-activation.
|
||||
|
||||
## What This Environment Provides
|
||||
|
||||
- Custom prompt showing the environment name
|
||||
- Environment-specific aliases and functions
|
||||
- Custom environment variables
|
||||
- Automatic cleanup when deactivated
|
||||
|
||||
## Requirements
|
||||
|
||||
- Fish shell
|
||||
- If this is a ROS2 environment: `bass` plugin (`fisher install edc/bass`)
|
||||
|
||||
## Sharing
|
||||
|
||||
This environment is completely self-contained. You can:
|
||||
1. Copy this directory to another machine
|
||||
2. Share it with other Fish shell users
|
||||
3. Version control it with your project (add .fish/ to your repo)
|
||||
|
||||
The environment will work on any system with Fish shell, regardless of whether
|
||||
they have the original environment management system installed.
|
||||
|
||||
## Auto-activation Setup
|
||||
|
||||
To enable auto-activation for .fish/activate.fish, add this to your Fish config.fish:
|
||||
```fish
|
||||
function check_and_source_activate
|
||||
if test -f (pwd)/.fish/activate.fish
|
||||
source (pwd)/.fish/activate.fish
|
||||
elif test -f (pwd)/activate.fish
|
||||
source (pwd)/activate.fish
|
||||
end
|
||||
end
|
||||
|
||||
function cd
|
||||
builtin cd $argv && check_and_source_activate
|
||||
end
|
||||
```
|
||||
74
.fish/activate.fish
Executable file
74
.fish/activate.fish
Executable file
@@ -0,0 +1,74 @@
|
||||
# Self-contained environment: ros2-lectures
|
||||
# Exported on: Thu Sep 25 10:57:14 AM CEST 2025
|
||||
# Original environment from: /home/wessel/.config/fish/environments/configs/ros2-lectures
|
||||
|
||||
# ROS2 development environment (requires distrobox)
|
||||
# Environment: ros2-lectures
|
||||
|
||||
# First check if running inside distrobox
|
||||
if not test -f /run/.containerenv; and test -z "$CONTAINER_ID"
|
||||
echo (set_color red)"This ROS2 environment should only be run inside a distrobox container"(set_color normal)
|
||||
return 1
|
||||
end
|
||||
|
||||
# Check if a previous initialization has occurred
|
||||
if test -n "$__ENV_INITIALIZED"
|
||||
echo (set_color yellow)"Environment already initialized"(set_color normal)
|
||||
return 0
|
||||
end
|
||||
|
||||
# Mark as initialized (only after distrobox check passes)
|
||||
set -gx __ENV_INITIALIZED "1"
|
||||
set -gx CURRENT_ENV "ros2-lectures"
|
||||
# Source ROS2 setup files using bass
|
||||
if type -q bass
|
||||
bass source /opt/ros/jazzy/setup.bash
|
||||
if test -f ./install/setup.bash
|
||||
bass source ./install/setup.bash
|
||||
end
|
||||
else
|
||||
echo (set_color red)"Error: bass is required for ROS2 environment. Install with: fisher install edc/bass"(set_color normal)
|
||||
return 1
|
||||
end
|
||||
|
||||
# Set environment variable for the prompt prefix
|
||||
set -gx ROS2_ACTIVE 1
|
||||
|
||||
# Save the original prompt function if it exists
|
||||
# Only save if we don't already have a backup or if current prompt is not from an environment
|
||||
if not functions -q __env_orig_prompt
|
||||
if functions -q fish_prompt
|
||||
functions -c fish_prompt __env_orig_prompt
|
||||
else
|
||||
function __env_orig_prompt
|
||||
echo -n (whoami)'@'(prompt_hostname)' '(set_color $fish_color_cwd)(prompt_pwd)(set_color normal)'> '
|
||||
end
|
||||
end
|
||||
else
|
||||
# If we already have a backup, we're switching environments
|
||||
# No need to create a new backup
|
||||
end
|
||||
|
||||
# Define new prompt with ROS2 prefix
|
||||
function fish_prompt
|
||||
echo -n (set_color magenta)'(ros2-lectures)'(set_color normal)' '
|
||||
__env_orig_prompt
|
||||
end
|
||||
|
||||
# ROS2 aliases and functions
|
||||
alias cb="colcon build"
|
||||
alias cbs="colcon build --symlink-install"
|
||||
alias cbt="colcon build --packages-select"
|
||||
alias ct="colcon test"
|
||||
alias ctr="colcon test-result"
|
||||
|
||||
echo (set_color green)"Activated ROS2 environment: ros2-lectures"(set_color normal)
|
||||
|
||||
# Custom deactivation function
|
||||
function __env_custom_deactivate
|
||||
# Remove ROS2-specific variables and aliases
|
||||
set -e ROS2_ACTIVE
|
||||
functions -e cb cbs cbt ct ctr 2>/dev/null
|
||||
|
||||
echo (set_color blue)"ROS2 environment cleanup completed"(set_color normal)
|
||||
end
|
||||
@@ -1,36 +0,0 @@
|
||||
export env_name="ros2-lectures"
|
||||
|
||||
# Check if a previous initialization has occurred
|
||||
if test -n "$__ACTIVATE_INITIALIZED"
|
||||
exit 1
|
||||
end
|
||||
|
||||
export __ACTIVATE_INITIALIZED="1"
|
||||
|
||||
# Check if running inside distrobox
|
||||
if test -f /run/.containerenv; or test -n "$CONTAINER_ID"
|
||||
bass source /opt/ros/jazzy/setup.bash
|
||||
bass source ./install/setup.bash
|
||||
# Set environment variable for the prompt prefix
|
||||
set -gx ROS2_LECTURES_ACTIVE 1
|
||||
|
||||
# Save the original prompt function if it exists
|
||||
if not functions -q __ros2_lectures_orig_prompt
|
||||
if functions -q fish_prompt
|
||||
functions -c fish_prompt __ros2_lectures_orig_prompt
|
||||
else
|
||||
function __ros2_lectures_orig_prompt
|
||||
echo -n (whoami)'@'(prompt_hostname)' '(set_color $fish_color_cwd)(prompt_pwd)(set_color normal)'> '
|
||||
end
|
||||
end
|
||||
end
|
||||
|
||||
# Define new prompt with ros2-lectures prefix
|
||||
function fish_prompt
|
||||
echo -n (set_color green)'('$env_name')'(set_color normal)
|
||||
__ros2_lectures_orig_prompt
|
||||
end
|
||||
else
|
||||
echo "This script should only be run inside a distrobox container"
|
||||
exit 1
|
||||
end
|
||||
BIN
slides/Lesson_1/Lesson_1.pdf
Normal file
BIN
slides/Lesson_1/Lesson_1.pdf
Normal file
Binary file not shown.
1
slides/Lesson_1/readme.md
Normal file
1
slides/Lesson_1/readme.md
Normal file
@@ -0,0 +1 @@
|
||||
Presentation lesson 1 25-09-2025
|
||||
125
src/les_pkg/src/les3/action_client.cpp
Normal file
125
src/les_pkg/src/les3/action_client.cpp
Normal file
@@ -0,0 +1,125 @@
|
||||
/* action_client.cpp
|
||||
* Action client node template for ROS2
|
||||
*
|
||||
* Node description:
|
||||
* Action client that sends goals to action server and handles responses,
|
||||
* feedback, and results. Demonstrates async goal sending and cancellation.
|
||||
*
|
||||
* Reviewed by: <x>
|
||||
* Changelog:
|
||||
* [18-09-2025] Wessel T: Implement action client template
|
||||
*/
|
||||
|
||||
// General includes
|
||||
#include <cstdlib>
|
||||
#include "rclcpp/rclcpp.hpp"
|
||||
#include "rclcpp_action/rclcpp_action.hpp"
|
||||
|
||||
// Custom includes
|
||||
#include "les_interface/action/template_a.hpp"
|
||||
|
||||
// Using declarations
|
||||
using TemplateA = les_interface::action::TemplateA;
|
||||
using TemplateAGoalHandle = rclcpp_action::ClientGoalHandle<TemplateA>;
|
||||
using namespace std::placeholders;
|
||||
|
||||
namespace lessons::three::actions {
|
||||
|
||||
class NodeActionClient : public rclcpp::Node {
|
||||
public:
|
||||
// Constructor:
|
||||
NodeActionClient() : Node("node_les3_action_client")
|
||||
{
|
||||
// Communication and timer objects:
|
||||
template_actionclient_ = rclcpp_action::create_client<TemplateA>(this, "template_actionserver");
|
||||
|
||||
RCLCPP_INFO(this->get_logger(), "Action client has been started.");
|
||||
}
|
||||
|
||||
// Communication and timer functions
|
||||
void sendGoal(std::string gname)
|
||||
{
|
||||
template_actionclient_->wait_for_action_server();
|
||||
auto goal = TemplateA::Goal();
|
||||
|
||||
goal.gname = gname;
|
||||
|
||||
auto options = rclcpp_action::Client<TemplateA>::SendGoalOptions();
|
||||
options.goal_response_callback = std::bind(&NodeActionClient::goalResponseCallback, this, _1);
|
||||
options.result_callback = std::bind(&NodeActionClient::goalResultCallback, this, _1);
|
||||
options.feedback_callback = std::bind(&NodeActionClient::goalFeedbackCallback, this, _1, _2);
|
||||
|
||||
template_actionclient_->async_send_goal(goal, options);
|
||||
RCLCPP_INFO(this->get_logger(), "Sent request");
|
||||
}
|
||||
|
||||
// Method to send a cancel request
|
||||
void cancelGoal()
|
||||
{
|
||||
RCLCPP_INFO(this->get_logger(), "Sent a cancel goal request");
|
||||
template_actionclient_->async_cancel_all_goals();
|
||||
}
|
||||
|
||||
private:
|
||||
// Communication and timer functions
|
||||
void goalResponseCallback(const TemplateAGoalHandle::SharedPtr &goal_handle)
|
||||
{
|
||||
if (!goal_handle) {
|
||||
RCLCPP_INFO(this->get_logger(), "Goal got rejected");
|
||||
}
|
||||
else {
|
||||
RCLCPP_INFO(this->get_logger(), "Goal got accepted");
|
||||
}
|
||||
}
|
||||
|
||||
void goalResultCallback(const TemplateAGoalHandle::WrappedResult &result)
|
||||
{
|
||||
auto status = result.code;
|
||||
if (status == rclcpp_action::ResultCode::SUCCEEDED) {
|
||||
RCLCPP_INFO(this->get_logger(), "Succeeded");
|
||||
}
|
||||
else if (status == rclcpp_action::ResultCode::ABORTED) {
|
||||
RCLCPP_ERROR(this->get_logger(), "Aborted");
|
||||
}
|
||||
else if (status == rclcpp_action::ResultCode::CANCELED) {
|
||||
RCLCPP_WARN(this->get_logger(), "Canceled");
|
||||
}
|
||||
int number = result.result->rnumber;
|
||||
RCLCPP_INFO(this->get_logger(), "Result: %d", number);
|
||||
}
|
||||
|
||||
void goalFeedbackCallback(const TemplateAGoalHandle::SharedPtr &goal_handle,
|
||||
const std::shared_ptr<const TemplateA::Feedback> feedback)
|
||||
{
|
||||
(void)goal_handle;
|
||||
int number = feedback->fnumber;
|
||||
RCLCPP_INFO(this->get_logger(), "Got feedback: %d", number);
|
||||
|
||||
// Now here the option to cancel request if
|
||||
// feedback has certain value
|
||||
|
||||
// if (number >= 2) {
|
||||
// cancelGoal();
|
||||
// }
|
||||
}
|
||||
|
||||
// Custom functions:
|
||||
// ...
|
||||
|
||||
// ROS2 variables:
|
||||
rclcpp_action::Client<TemplateA>::SharedPtr template_actionclient_;
|
||||
};
|
||||
|
||||
} // namespace lessons::three::actions
|
||||
|
||||
int main(int argc, char *argv[]) {
|
||||
rclcpp::init(argc, argv);
|
||||
auto node = std::make_shared<lessons::three::actions::NodeActionClient>();
|
||||
|
||||
std::string name = "jan";
|
||||
node->sendGoal(name);
|
||||
|
||||
rclcpp::spin(node);
|
||||
rclcpp::shutdown();
|
||||
return 0;
|
||||
}
|
||||
22
src/robot_description/.vscode/c_cpp_properties.json
vendored
Normal file
22
src/robot_description/.vscode/c_cpp_properties.json
vendored
Normal file
@@ -0,0 +1,22 @@
|
||||
{
|
||||
"configurations": [
|
||||
{
|
||||
"browse": {
|
||||
"databaseFilename": "${default}",
|
||||
"limitSymbolsToIncludedHeaders": false
|
||||
},
|
||||
"includePath": [
|
||||
"/home/wessel/Documents/ros2-lectures/install/les_interface/include/**",
|
||||
"/opt/ros/jazzy/include/**",
|
||||
"/home/wessel/Documents/ros2-lectures/src/les_pkg/include/**",
|
||||
"/usr/include/**"
|
||||
],
|
||||
"name": "ROS",
|
||||
"intelliSenseMode": "gcc-x64",
|
||||
"compilerPath": "/usr/bin/gcc",
|
||||
"cStandard": "gnu11",
|
||||
"cppStandard": "c++14"
|
||||
}
|
||||
],
|
||||
"version": 4
|
||||
}
|
||||
10
src/robot_description/.vscode/settings.json
vendored
Normal file
10
src/robot_description/.vscode/settings.json
vendored
Normal file
@@ -0,0 +1,10 @@
|
||||
{
|
||||
"python.autoComplete.extraPaths": [
|
||||
"/home/wessel/Documents/ros2-lectures/install/les_interface/lib/python3.12/site-packages",
|
||||
"/opt/ros/jazzy/lib/python3.12/site-packages"
|
||||
],
|
||||
"python.analysis.extraPaths": [
|
||||
"/home/wessel/Documents/ros2-lectures/install/les_interface/lib/python3.12/site-packages",
|
||||
"/opt/ros/jazzy/lib/python3.12/site-packages"
|
||||
]
|
||||
}
|
||||
17
src/robot_description/CMakeLists.txt
Normal file
17
src/robot_description/CMakeLists.txt
Normal file
@@ -0,0 +1,17 @@
|
||||
cmake_minimum_required(VERSION 3.8)
|
||||
project(robot_description)
|
||||
|
||||
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
|
||||
add_compile_options(-Wall -Wextra -Wpedantic)
|
||||
endif()
|
||||
|
||||
# find dependencies
|
||||
find_package(ament_cmake REQUIRED)
|
||||
|
||||
# Install directories
|
||||
install(
|
||||
DIRECTORY launch meshes urdf rviz
|
||||
DESTINATION share/${PROJECT_NAME}
|
||||
)
|
||||
|
||||
ament_package()
|
||||
26
src/robot_description/launch/display.launch.xml
Normal file
26
src/robot_description/launch/display.launch.xml
Normal file
@@ -0,0 +1,26 @@
|
||||
<launch>
|
||||
<let name="urdf_path"
|
||||
value="$(find-pkg-share robot_description)/urdf/skyentific_robot.urdf.xacro"
|
||||
/>
|
||||
|
||||
<let name="rviz_config_path"
|
||||
value="$(find-pkg-share robot_description)/rviz/urdf_config.rviz"
|
||||
/>
|
||||
|
||||
<node pkg="robot_state_publisher"
|
||||
exec="robot_state_publisher"
|
||||
>
|
||||
<param name="robot_description"
|
||||
value="$(command 'xacro $(var urdf_path)')"/>
|
||||
</node>
|
||||
|
||||
<node pkg="joint_state_publisher_gui"
|
||||
exec="joint_state_publisher_gui"
|
||||
/>
|
||||
|
||||
<node pkg="rviz2"
|
||||
exec="rviz2"
|
||||
output="screen"
|
||||
args="-d $(var rviz_config_path)"
|
||||
/>
|
||||
</launch>
|
||||
BIN
src/robot_description/meshes/base_z_ob.stl
Normal file
BIN
src/robot_description/meshes/base_z_ob.stl
Normal file
Binary file not shown.
BIN
src/robot_description/meshes/leftjaw.stl
Normal file
BIN
src/robot_description/meshes/leftjaw.stl
Normal file
Binary file not shown.
BIN
src/robot_description/meshes/link_1.stl
Normal file
BIN
src/robot_description/meshes/link_1.stl
Normal file
Binary file not shown.
BIN
src/robot_description/meshes/link_2.stl
Normal file
BIN
src/robot_description/meshes/link_2.stl
Normal file
Binary file not shown.
BIN
src/robot_description/meshes/link_3.stl
Normal file
BIN
src/robot_description/meshes/link_3.stl
Normal file
Binary file not shown.
BIN
src/robot_description/meshes/link_4.stl
Normal file
BIN
src/robot_description/meshes/link_4.stl
Normal file
Binary file not shown.
BIN
src/robot_description/meshes/link_5.stl
Normal file
BIN
src/robot_description/meshes/link_5.stl
Normal file
Binary file not shown.
BIN
src/robot_description/meshes/link_5_gripper.stl
Normal file
BIN
src/robot_description/meshes/link_5_gripper.stl
Normal file
Binary file not shown.
1
src/robot_description/meshes/readme.md
Normal file
1
src/robot_description/meshes/readme.md
Normal file
@@ -0,0 +1 @@
|
||||
meshes to be used with lesson 1
|
||||
BIN
src/robot_description/meshes/rightjaw.stl
Normal file
BIN
src/robot_description/meshes/rightjaw.stl
Normal file
Binary file not shown.
15
src/robot_description/package.xml
Normal file
15
src/robot_description/package.xml
Normal file
@@ -0,0 +1,15 @@
|
||||
<?xml version="1.0"?>
|
||||
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
|
||||
<package format="3">
|
||||
<name>robot_description</name>
|
||||
<version>0.0.0</version>
|
||||
<description>TODO: Package description</description>
|
||||
<maintainer email="wessel@go2it.eu">wessel</maintainer>
|
||||
<license>TODO: License declaration</license>
|
||||
|
||||
<buildtool_depend>ament_cmake</buildtool_depend>
|
||||
|
||||
<export>
|
||||
<build_type>ament_cmake</build_type>
|
||||
</export>
|
||||
</package>
|
||||
239
src/robot_description/rviz/display.rviz
Normal file
239
src/robot_description/rviz/display.rviz
Normal file
@@ -0,0 +1,239 @@
|
||||
Panels:
|
||||
- Class: rviz_common/Displays
|
||||
Help Height: 85
|
||||
Name: Displays
|
||||
Property Tree Widget:
|
||||
Expanded:
|
||||
- /Global Options1
|
||||
- /Status1
|
||||
- /RobotModel1/Description Topic1
|
||||
Splitter Ratio: 0.5
|
||||
Tree Height: 517
|
||||
- Class: rviz_common/Selection
|
||||
Name: Selection
|
||||
- Class: rviz_common/Tool Properties
|
||||
Expanded:
|
||||
- /2D Goal Pose1
|
||||
- /Publish Point1
|
||||
Name: Tool Properties
|
||||
Splitter Ratio: 0.5886790156364441
|
||||
- Class: rviz_common/Views
|
||||
Expanded:
|
||||
- /Current View1
|
||||
Name: Views
|
||||
Splitter Ratio: 0.5
|
||||
- Class: rviz_common/Time
|
||||
Experimental: false
|
||||
Name: Time
|
||||
SyncMode: 0
|
||||
SyncSource: ""
|
||||
Visualization Manager:
|
||||
Class: ""
|
||||
Displays:
|
||||
- Alpha: 0.5
|
||||
Cell Size: 1
|
||||
Class: rviz_default_plugins/Grid
|
||||
Color: 160; 160; 164
|
||||
Enabled: true
|
||||
Line Style:
|
||||
Line Width: 0.029999999329447746
|
||||
Value: Lines
|
||||
Name: Grid
|
||||
Normal Cell Count: 0
|
||||
Offset:
|
||||
X: 0
|
||||
Y: 0
|
||||
Z: 0
|
||||
Plane: XY
|
||||
Plane Cell Count: 10
|
||||
Reference Frame: <Fixed Frame>
|
||||
Value: true
|
||||
- Alpha: 1
|
||||
Class: rviz_default_plugins/RobotModel
|
||||
Collision Enabled: false
|
||||
Description File: ""
|
||||
Description Source: Topic
|
||||
Description Topic:
|
||||
Depth: 5
|
||||
Durability Policy: Volatile
|
||||
History Policy: Keep Last
|
||||
Reliability Policy: Reliable
|
||||
Value: /robot_description
|
||||
Enabled: true
|
||||
Links:
|
||||
All Links Enabled: true
|
||||
Expand Joint Details: false
|
||||
Expand Link Details: false
|
||||
Expand Tree: false
|
||||
Link Tree Style: Links in Alphabetic Order
|
||||
arm_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
base_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
elbow_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
forearm_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
hand_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
shoulder_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
tool_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
wrist_link:
|
||||
Alpha: 1
|
||||
Show Axes: false
|
||||
Show Trail: false
|
||||
Value: true
|
||||
Mass Properties:
|
||||
Inertia: false
|
||||
Mass: false
|
||||
Name: RobotModel
|
||||
TF Prefix: ""
|
||||
Update Interval: 0
|
||||
Value: true
|
||||
Visual Enabled: true
|
||||
- Class: rviz_default_plugins/TF
|
||||
Enabled: true
|
||||
Filter (blacklist): ""
|
||||
Filter (whitelist): ""
|
||||
Frame Timeout: 15
|
||||
Frames:
|
||||
All Enabled: true
|
||||
arm_link:
|
||||
Value: true
|
||||
base_link:
|
||||
Value: true
|
||||
elbow_link:
|
||||
Value: true
|
||||
forearm_link:
|
||||
Value: true
|
||||
hand_link:
|
||||
Value: true
|
||||
shoulder_link:
|
||||
Value: true
|
||||
tool_link:
|
||||
Value: true
|
||||
wrist_link:
|
||||
Value: true
|
||||
Marker Scale: 1
|
||||
Name: TF
|
||||
Show Arrows: true
|
||||
Show Axes: true
|
||||
Show Names: false
|
||||
Tree:
|
||||
base_link:
|
||||
shoulder_link:
|
||||
arm_link:
|
||||
elbow_link:
|
||||
forearm_link:
|
||||
wrist_link:
|
||||
hand_link:
|
||||
tool_link:
|
||||
{}
|
||||
Update Interval: 0
|
||||
Value: true
|
||||
Enabled: true
|
||||
Global Options:
|
||||
Background Color: 48; 48; 48
|
||||
Fixed Frame: base_link
|
||||
Frame Rate: 30
|
||||
Name: root
|
||||
Tools:
|
||||
- Class: rviz_default_plugins/Interact
|
||||
Hide Inactive Objects: true
|
||||
- Class: rviz_default_plugins/MoveCamera
|
||||
- Class: rviz_default_plugins/Select
|
||||
- Class: rviz_default_plugins/FocusCamera
|
||||
- Class: rviz_default_plugins/Measure
|
||||
Line color: 128; 128; 0
|
||||
- Class: rviz_default_plugins/SetInitialPose
|
||||
Covariance x: 0.25
|
||||
Covariance y: 0.25
|
||||
Covariance yaw: 0.06853891909122467
|
||||
Topic:
|
||||
Depth: 5
|
||||
Durability Policy: Volatile
|
||||
History Policy: Keep Last
|
||||
Reliability Policy: Reliable
|
||||
Value: /initialpose
|
||||
- Class: rviz_default_plugins/SetGoal
|
||||
Topic:
|
||||
Depth: 5
|
||||
Durability Policy: Volatile
|
||||
History Policy: Keep Last
|
||||
Reliability Policy: Reliable
|
||||
Value: /goal_pose
|
||||
- Class: rviz_default_plugins/PublishPoint
|
||||
Single click: true
|
||||
Topic:
|
||||
Depth: 5
|
||||
Durability Policy: Volatile
|
||||
History Policy: Keep Last
|
||||
Reliability Policy: Reliable
|
||||
Value: /clicked_point
|
||||
Transformation:
|
||||
Current:
|
||||
Class: rviz_default_plugins/TF
|
||||
Value: true
|
||||
Views:
|
||||
Current:
|
||||
Class: rviz_default_plugins/Orbit
|
||||
Distance: 3.4432098865509033
|
||||
Enable Stereo Rendering:
|
||||
Stereo Eye Separation: 0.05999999865889549
|
||||
Stereo Focal Distance: 1
|
||||
Swap Stereo Eyes: false
|
||||
Value: false
|
||||
Focal Point:
|
||||
X: -0.299166202545166
|
||||
Y: -0.3069069981575012
|
||||
Z: 0.8311280012130737
|
||||
Focal Shape Fixed Size: true
|
||||
Focal Shape Size: 0.05000000074505806
|
||||
Invert Z Axis: false
|
||||
Name: Current View
|
||||
Near Clip Distance: 0.009999999776482582
|
||||
Pitch: 0.3503985106945038
|
||||
Target Frame: <Fixed Frame>
|
||||
Value: Orbit (rviz)
|
||||
Yaw: 0.5403982400894165
|
||||
Saved: ~
|
||||
Window Geometry:
|
||||
Displays:
|
||||
collapsed: false
|
||||
Height: 854
|
||||
Hide Left Dock: false
|
||||
Hide Right Dock: false
|
||||
QMainWindow State: 000000ff00000000fd000000040000000000000160000002a3fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006f00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730100000048000002a3000000f300fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002a3fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730000000048000002a3000000c500fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004bd00000042fc0100000002fb0000000800540069006d00650100000000000004bd000002dc00fffffffb0000000800540069006d0065010000000000000450000000000000000000000356000002a300000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
|
||||
Selection:
|
||||
collapsed: false
|
||||
Time:
|
||||
collapsed: false
|
||||
Tool Properties:
|
||||
collapsed: false
|
||||
Views:
|
||||
collapsed: false
|
||||
Width: 1213
|
||||
X: 400
|
||||
Y: 84
|
||||
1
src/robot_description/rviz/readme.md
Normal file
1
src/robot_description/rviz/readme.md
Normal file
@@ -0,0 +1 @@
|
||||
rviz2 config file
|
||||
263
src/robot_description/urdf/skyentific_robot.urdf.xacro
Normal file
263
src/robot_description/urdf/skyentific_robot.urdf.xacro
Normal file
@@ -0,0 +1,263 @@
|
||||
<?xml version="1.0"?>
|
||||
<robot
|
||||
name="skyentific_robot"
|
||||
xmlns:xacro="http://www.ros.org/wiki/xacro"
|
||||
>
|
||||
<!-- Include ros2_control Plugins -->
|
||||
<xacro:include
|
||||
filename="$(find robot_description)/urdf/skyentific_robot_ros2_control.xacro"
|
||||
/>
|
||||
<!-- Useful XACRO Variables (Properties) -->
|
||||
<xacro:property name="PI" value="3.14159265359" />
|
||||
<material name="grey">
|
||||
<color rgba="0.5 0.5 0.5 1.0"/>
|
||||
</material>
|
||||
<material name="red">
|
||||
<color rgba="0.5 0.0 0.0 1.0"/>
|
||||
</material>
|
||||
|
||||
<link name="base_link">
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="file://$(find robot_description)/meshes/base_z_ob.stl"
|
||||
scale="0.001 0.001 0.001"
|
||||
/>
|
||||
</geometry>
|
||||
<material name="grey" />
|
||||
</visual>
|
||||
<collision> <!-- cyclinder equivalent -->
|
||||
<origin xyz="0 0 0.075" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder radius="0.1" length="0.15"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<link name="link_1">
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="file://$(find robot_description)/meshes/link_1.stl"
|
||||
scale="0.001 0.001 0.001"
|
||||
/>
|
||||
</geometry>
|
||||
<material name="grey" />
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0.150" rpy="1.57 0 0"/>
|
||||
<geometry>
|
||||
<cylinder radius="0.095" length="0.1"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="joint_1" type="revolute">
|
||||
<parent link="base_link"/>
|
||||
<child link="link_1"/>
|
||||
<origin xyz="0 0 0.0965" rpy="0 0 0"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit
|
||||
effort="1000.0"
|
||||
velocity="100.0"
|
||||
lower="-3.14"
|
||||
upper="3.14"
|
||||
/>
|
||||
</joint>
|
||||
|
||||
<link name="link_2">
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="file://$(find robot_description)/meshes/link_2.stl"
|
||||
scale="0.001 0.001 0.001"
|
||||
/>
|
||||
</geometry>
|
||||
<material name="grey"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0.225 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder radius="0.07" length="0.1"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="joint_2" type="revolute">
|
||||
<parent link="link_1"/>
|
||||
<child link="link_2"/>
|
||||
<origin xyz="0 0 0.150" rpy="0 -1.57 1.57"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit
|
||||
effort="1000.0"
|
||||
velocity="100.0"
|
||||
lower="-2.51"
|
||||
upper="2.51"
|
||||
/>
|
||||
</joint>
|
||||
|
||||
<link name="link_3">
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="file://$(find robot_description)/meshes/link_3.stl"
|
||||
scale="0.001 0.001 0.001"
|
||||
/>
|
||||
</geometry>
|
||||
<material name="grey" />
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0.2 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder radius="0.055" length="0.1"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="joint_3" type="revolute">
|
||||
<parent link="link_2"/>
|
||||
<child link="link_3"/>
|
||||
<origin xyz="0.225 0 0" rpy="0 0 0"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit
|
||||
effort="1000.0"
|
||||
velocity="100.0"
|
||||
lower="-2.51"
|
||||
upper="2.51"
|
||||
/>
|
||||
</joint>
|
||||
|
||||
<link name="link_4">
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="file://$(find robot_description)/meshes/link_4.stl"
|
||||
scale="0.001 0.001 0.001"
|
||||
/>
|
||||
</geometry>
|
||||
<material name="grey" />
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0.1 0 0" rpy="0 1.57 0"/>
|
||||
<geometry>
|
||||
<cylinder radius="0.055" length="0.06"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="joint_4" type="revolute">
|
||||
<parent link="link_3"/>
|
||||
<child link="link_4"/>
|
||||
<origin xyz="0.2 0 0" rpy="0 0 0"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit
|
||||
effort="1000.0"
|
||||
velocity="100.0"
|
||||
lower="-2.51"
|
||||
upper="2.51"
|
||||
/>
|
||||
</joint>
|
||||
|
||||
<link name="link_5">
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="file://$(find robot_description)/meshes/link_5_gripper.stl"
|
||||
scale="0.001 0.001 0.001"
|
||||
/>
|
||||
</geometry>
|
||||
<material name="grey" />
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="1.57 0 0"/>
|
||||
<geometry>
|
||||
<cylinder radius="0.055" length="0.01"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="joint_5" type="revolute">
|
||||
<parent link="link_4"/>
|
||||
<child link="link_5"/>
|
||||
<origin xyz="0.0915 0 0" rpy="0 1.57 0"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit
|
||||
effort="1000.0"
|
||||
velocity="100.0"
|
||||
lower="-2.51"
|
||||
upper="2.51"
|
||||
/>
|
||||
</joint>
|
||||
|
||||
<link name="gripper_right">
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="file://$(find robot_description)/meshes/rightjaw.stl"
|
||||
scale="0.001 0.001 0.001"
|
||||
/>
|
||||
</geometry>
|
||||
<material name="red"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0.01 0.025 0.045" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder radius="0.0125" length="0.04"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="joint_6" type="prismatic">
|
||||
<parent link="link_5"/>
|
||||
<child link="gripper_right"/>
|
||||
<origin xyz="-0.01 0 0.1015" rpy="0 0 0"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<limit
|
||||
effort="1000.0"
|
||||
velocity="100.0"
|
||||
lower="-0.018"
|
||||
upper="0.02"
|
||||
/>
|
||||
</joint>
|
||||
|
||||
<link name="gripper_left">
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh
|
||||
filename="file://$(find robot_description)/meshes/leftjaw.stl"
|
||||
scale="0.001 0.001 0.001"
|
||||
/>
|
||||
</geometry>
|
||||
<material name="red"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0.01 -0.025 0.045" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder radius="0.0125" length="0.04"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="joint_7" type="prismatic">
|
||||
<parent link="link_5"/>
|
||||
<child link="gripper_left"/>
|
||||
<origin xyz="-0.01 0 0.1015" rpy="0 0 0"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<mimic joint="joint_6" multiplier="-1"/>
|
||||
<limit
|
||||
effort="1000.0"
|
||||
velocity="100.0"
|
||||
lower="-0.018"
|
||||
upper="0.02"
|
||||
/>
|
||||
</joint>
|
||||
|
||||
</robot>
|
||||
@@ -0,0 +1,26 @@
|
||||
<?xml version="1.0"?>
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
<ros2_control name="Arm" type="system">
|
||||
<hardware>
|
||||
<plugin>mock_components/GenericSystem</plugin>
|
||||
</hardware>
|
||||
<joint name="joint_1">
|
||||
<command_interface name="position"/>
|
||||
<state_interface name="position">
|
||||
<param name="initial_value">0.0</param>
|
||||
</state_interface>
|
||||
</joint>
|
||||
</ros2_control>
|
||||
|
||||
<ros2_control name="Gripper" type="system">
|
||||
<hardware>
|
||||
<plugin>mock_components/GenericSystem</plugin>
|
||||
</hardware>
|
||||
<joint name="joint_6">
|
||||
<command_interface name="position"/>
|
||||
<state_interface name="position">
|
||||
<param name="initial_value">0.0</param>
|
||||
</state_interface>
|
||||
</joint>
|
||||
</ros2_control>
|
||||
</robot>
|
||||
Reference in New Issue
Block a user