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

Add light weight suction gripper with updated multicopter velocity controller #196

Merged
merged 1 commit into from
Jul 29, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
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
5 changes: 5 additions & 0 deletions mbzirc_ign/models/mbzirc_hexrotor/model.sdf.erb
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@ end

$attitude_gain = '4 4 2'
$motor_constant = '1.269e-05'
$thrust_with_payload_mass = '0'
if defined?($gripper_model)
if $gripper_model.include?('mbzirc_oberon7_gripper')
$attitude_gain = '25 25 2'
Expand All @@ -19,6 +20,9 @@ if defined?($gripper_model)
$attitude_gain = '25 25 2'
$motor_constant = '1.40e-05'
end
if $gripper_model.include?('_light')
$thrust_with_payload_mass = '1'
end
end

$slot0_payload = nil
Expand Down Expand Up @@ -435,6 +439,7 @@ end
<direction>-1</direction>
</rotor>
</rotorConfiguration>
<thrustWithPayloadMass><%= $thrust_with_payload_mass %></thrustWithPayloadMass>
</plugin>
<!-- Battery plugin -->
<plugin filename="libignition-gazebo-linearbatteryplugin-system.so"
Expand Down
5 changes: 5 additions & 0 deletions mbzirc_ign/models/mbzirc_quadrotor/model.sdf.erb
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@ end

$attitude_gain = '2 3 0.15'
$motor_constant = '8.54858e-06'
$thrust_with_payload_mass = '0'
if defined?($gripper_model)
if $gripper_model.include?('mbzirc_oberon7_gripper')
$attitude_gain = '10 10 0.15'
Expand All @@ -19,6 +20,9 @@ if defined?($gripper_model)
$attitude_gain = '10 10 0.15'
$motor_constant = '2.52e-05'
end
if $gripper_model.include?('_light')
$thrust_with_payload_mass = '1'
end
end

$slot0_payload = nil
Expand Down Expand Up @@ -377,6 +381,7 @@ end
<direction>-1</direction>
</rotor>
</rotorConfiguration>
<thrustWithPayloadMass><%= $thrust_with_payload_mass %></thrustWithPayloadMass>
</plugin>
<!-- Battery plugin -->
<!-- Since we are interested in using time as the limiting factor -->
Expand Down
11 changes: 11 additions & 0 deletions mbzirc_ign/models/mbzirc_suction_gripper_light/model.config
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
<?xml version="1.0"?>

<model>
<name>MBZIRC Suction Gripper Light</name>
<version>1.0</version>
<sdf version="1.9">model.sdf</sdf>

<description>
Lightweight version of the suction gripper for MBZIRC
</description>
</model>
234 changes: 234 additions & 0 deletions mbzirc_ign/models/mbzirc_suction_gripper_light/model.sdf.erb
Original file line number Diff line number Diff line change
@@ -0,0 +1,234 @@
<%
if !defined?(topic_prefix) || topic_prefix == nil || topic_prefix.empty?
$topic_prefix = ''
else
$topic_prefix = topic_prefix
end
%>

<?xml version="1.0" ?>
<sdf version='1.9'>
<model name="suction_gripper">
<link name='end_effector'>
<inertial>
<mass>1</mass>
<inertia>
<ixx>0.00166667</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.00166667</iyy>
<iyz>0</iyz>
<izz>0.00166667</izz>
</inertia>
</inertial>
<collision name='end_effector_collision'>
<pose>0.025 0 0 0 1.57079 0</pose>
<geometry>
<cylinder>
<radius>0.05</radius>
<length>0.05</length>
</cylinder>
</geometry>
</collision>
<visual name='end_effector_visual'>
<pose>0.025 0 0 0 1.57079 0</pose>
<geometry>
<cylinder>
<radius>0.05</radius>
<length>0.05</length>
</cylinder>
</geometry>
<material>
<diffuse>0.05 0.15 0.05</diffuse>
<specular>0.8 0.8 0.8</specular>
</material>
</visual>
</link>
<link name='suction'>
<inertial>
<mass>1</mass>
<inertia>
<ixx>0.00166667</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.00166667</iyy>
<iyz>0</iyz>
<izz>0.00166667</izz>
</inertia>
</inertial>

<collision name='suction_collision_11'>
<pose>0.0505 0 0 0 1.57079 0</pose>
<geometry>
<cylinder>
<radius>0.02</radius>
<length>0.01</length>
</cylinder>
</geometry>
</collision>
<visual name='suction_visual_11'>
<pose>0.0505 0 0 0 1.57079 0</pose>
<geometry>
<cylinder>
<radius>0.02</radius>
<length>0.01</length>
</cylinder>
</geometry>
<material>
<diffuse>0.02 0.02 0.02</diffuse>
<specular>0.3 0.3 0.3</specular>
</material>
</visual>
<sensor name='sensor_contact_11' type='contact'>
<contact>
<collision>suction_collision_11</collision>
<topic><%= $topic_prefix %>/gripper/contact_sensor_11</topic>
</contact>
<always_on>1</always_on>
<update_rate>100</update_rate>
</sensor>

<collision name='suction_collision_10'>
<pose>0.0505 0 -0.04 0 1.57079 0</pose>
<geometry>
<cylinder>
<radius>0.02</radius>
<length>0.01</length>
</cylinder>
</geometry>
</collision>
<visual name='suction_visual_10'>
<pose>0.0505 0 -0.04 0 1.57079 0</pose>
<geometry>
<cylinder>
<radius>0.02</radius>
<length>0.01</length>
</cylinder>
</geometry>
<material>
<diffuse>0.02 0.02 0.02</diffuse>
<specular>0.3 0.3 0.3</specular>
</material>
</visual>
<sensor name='sensor_contact_10' type='contact'>
<contact>
<collision>suction_collision_10</collision>
<topic><%= $topic_prefix %>/gripper/contact_sensor_10</topic>
</contact>
<always_on>1</always_on>
<update_rate>100</update_rate>
</sensor>

<collision name='suction_collision_12'>
<pose>0.0505 0 0.04 0 1.57079 0</pose>
<geometry>
<cylinder>
<radius>0.02</radius>
<length>0.01</length>
</cylinder>
</geometry>
</collision>
<visual name='suction_visual_12'>
<pose>0.0505 0 0.04 0 1.57079 0</pose>
<geometry>
<cylinder>
<radius>0.02</radius>
<length>0.01</length>
</cylinder>
</geometry>
<material>
<diffuse>0.02 0.02 0.02</diffuse>
<specular>0.3 0.3 0.3</specular>
</material>
</visual>
<sensor name='sensor_contact_12' type='contact'>
<contact>
<collision>suction_collision_12</collision>
<topic><%= $topic_prefix %>/gripper/contact_sensor_12</topic>
</contact>
<always_on>1</always_on>
<update_rate>100</update_rate>
</sensor>

<collision name='suction_collision_01'>
<pose>0.0505 -0.04 0 0 1.57079 0</pose>
<geometry>
<cylinder>
<radius>0.02</radius>
<length>0.01</length>
</cylinder>
</geometry>
</collision>
<visual name='suction_visual_01'>
<pose>0.0505 -0.04 0 0 1.57079 0</pose>
<geometry>
<cylinder>
<radius>0.02</radius>
<length>0.01</length>
</cylinder>
</geometry>
<material>
<diffuse>0.02 0.02 0.02</diffuse>
<specular>0.3 0.3 0.3</specular>
</material>
</visual>
<sensor name='sensor_contact_01' type='contact'>
<contact>
<collision>suction_collision_01</collision>
<topic><%= $topic_prefix %>/gripper/contact_sensor_01</topic>
</contact>
<always_on>1</always_on>
<update_rate>100</update_rate>
</sensor>

<collision name='suction_collision_21'>
<pose>0.0505 0.04 0 0 1.57079 0</pose>
<geometry>
<cylinder>
<radius>0.02</radius>
<length>0.01</length>
</cylinder>
</geometry>
</collision>
<visual name='suction_visual_21'>
<pose>0.0505 0.04 0 0 1.57079 0</pose>
<geometry>
<cylinder>
<radius>0.02</radius>
<length>0.01</length>
</cylinder>
</geometry>
<material>
<diffuse>0.02 0.02 0.02</diffuse>
<specular>0.3 0.3 0.3</specular>
</material>
</visual>
<sensor name='sensor_contact_21' type='contact'>
<contact>
<collision>suction_collision_21</collision>
<topic><%= $topic_prefix %>/gripper/contact_sensor_21</topic>
</contact>
<always_on>1</always_on>
<update_rate>100</update_rate>
</sensor>

</link>

<joint name='suction_joint' type='fixed'>
<parent>end_effector</parent>
<child>suction</child>
</joint>

<!-- Controller -->
<plugin
filename="libSuctionGripper.so"
name="mbzirc::SuctionGripperPlugin">
<parent_link>suction</parent_link>
<contact_sensor_topic_prefix><%= $topic_prefix %>/gripper</contact_sensor_topic_prefix>
<command_topic><%= $topic_prefix %>/gripper/suction_on</command_topic>
</plugin>

<frame name="mount_point"/>

</model>
</sdf>
7 changes: 4 additions & 3 deletions mbzirc_ign/src/mbzirc_ign/model.py
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,8 @@

GRIPPERS = [
'mbzirc_oberon7_gripper',
'mbzirc_suction_gripper'
'mbzirc_suction_gripper',
'mbzirc_suction_gripper_light',
]

WAVEFIELD_SIZE = {'simple_demo': 1000, 'coast': 6000}
Expand Down Expand Up @@ -159,7 +160,7 @@ def bridges(self, world_name):
if self.has_valid_gripper():
isAttachedToArm = self.is_USV()
# gripper joint pos cmd
if self.gripper == 'mbzirc_oberon7_gripper':
if 'mbzirc_oberon7_gripper' in self.gripper:
# gripper_joint states
bridges.append(
mbzirc_ign.bridges.gripper_joint_states(world_name, self.model_name,
Expand All @@ -175,7 +176,7 @@ def bridges(self, world_name):
mbzirc_ign.bridges.gripper_joint_force_torque(
self.model_name, joint, isAttachedToArm)
)
elif self.gripper == 'mbzirc_suction_gripper':
elif 'mbzirc_suction_gripper' in self.gripper:
bridges.append(
mbzirc_ign.bridges.gripper_suction_control(self.model_name, isAttachedToArm)
)
Expand Down
7 changes: 4 additions & 3 deletions mbzirc_ign/src/multicopter_control/LeeVelocityController.cc
Original file line number Diff line number Diff line change
Expand Up @@ -86,7 +86,7 @@ bool LeeVelocityController::InitializeParameters()

//////////////////////////////////////////////////
void LeeVelocityController::CalculateRotorVelocities(
const FrameData &_frameData, const EigenTwist &_cmdVel,
const FrameData &_frameData, double _payloadMass, const EigenTwist &_cmdVel,
Eigen::VectorXd &_rotorVelocities) const
{
Eigen::Vector3d acceleration =
Expand All @@ -96,8 +96,9 @@ void LeeVelocityController::CalculateRotorVelocities(
this->ComputeDesiredAngularAcc(_frameData, _cmdVel, acceleration);

// Project thrust onto body z axis.
double thrust = -this->vehicleParameters.mass *
acceleration.dot(_frameData.pose.linear().col(2));
double massWithPayload = this->vehicleParameters.mass + _payloadMass;
double thrust = -massWithPayload *
acceleration.dot(_frameData.pose.linear().col(2));

Eigen::Vector4d angularAccelerationThrust;
angularAccelerationThrust.block<3, 1>(0, 0) = angularAcceleration;
Expand Down
2 changes: 2 additions & 0 deletions mbzirc_ign/src/multicopter_control/LeeVelocityController.hh
Original file line number Diff line number Diff line change
Expand Up @@ -64,10 +64,12 @@ namespace multicopter_control
/// commanded velocity
/// \param[in] _frameData Frame data including pose and linear and angular
/// velocities
/// \param[in] _payloadMass Mass of payload
/// \param[in] _cmdVel Commanded velocity
/// \param[out] _rotorVelocities Computed rotor velocities.
public: void CalculateRotorVelocities(
const FrameData &_frameData,
double _payloadMass,
const EigenTwist &_cmdVel,
Eigen::VectorXd &_rotorVelocities) const;

Expand Down
Loading