Skip to content
This repository has been archived by the owner on Dec 10, 2019. It is now read-only.

Commit

Permalink
Merge pull request #3 from AcutronicRobotics/dashing
Browse files Browse the repository at this point in the history
Dashing
  • Loading branch information
ahcorde authored Jun 13, 2019
2 parents 67a4f00 + a4674cb commit f635475
Show file tree
Hide file tree
Showing 14 changed files with 115 additions and 140 deletions.
5 changes: 2 additions & 3 deletions gripper_minimal_service/scripts/gripper_minimal_client_v1.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,14 +12,13 @@
node = rclpy.create_node("mara_minimal_client")

# Create a client for service "/hrim_actuation_gripper_000000000004/goal"
client = node.create_client(ControlFinger, "/hrim_actuation_gripper_000000000004/goal", qos_profile=qos_profile_services_default)
client = node.create_client(ControlFinger, "/hrim_actuator_gripper_000000000004/fingercontrol", qos_profile=qos_profile_services_default)

# Create request with the same type as the service, ControlFinger
req = ControlFinger.Request()

# Position range 0 - 0.87 rad
# TODO: The range is wider for me (up to 9.0 sometimes)
req.goal_linearposition = 0.87
req.goal_angularposition = 0.

# Wait for service to be avaiable before calling it
while not client.wait_for_service(timeout_sec=1.0):
Expand Down
4 changes: 2 additions & 2 deletions gripper_minimal_service/scripts/gripper_minimal_client_v2.py
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ def __init__(self):
super().__init__('mara_minimal_client')

# Create a client for service "/hrim_actuation_gripper_000000000004/goal"
self.client = self.create_client(ControlFinger, "/hrim_actuation_gripper_000000000004/goal")
self.client = self.create_client(ControlFinger, "/hrim_actuator_gripper_000000000004/fingercontrol")

# Wait for service to be avaiable before calling it
while not self.client.wait_for_service(timeout_sec=1.0):
Expand All @@ -21,7 +21,7 @@ def __init__(self):
self.req = ControlFinger.Request()

def send_request(self):
self.req.goal_linearposition = 0.87
self.req.goal_angularposition = 0.
self.future = self.client.call_async(self.req)


Expand Down
4 changes: 2 additions & 2 deletions gripper_minimal_service/src/gripper_minimal_client_v1.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,13 +13,13 @@ int main(int argc, char ** argv)
auto node = rclcpp::Node::make_shared("mara_minimal_client");

// Create a client for service "/hrim_actuation_gripper_000000000004/goal"
auto client = node->create_client<hrim_actuator_gripper_srvs::srv::ControlFinger>("/hrim_actuation_gripper_000000000004/goal");
auto client = node->create_client<hrim_actuator_gripper_srvs::srv::ControlFinger>("/hrim_actuator_gripper_000000000004/fingercontrol");

// Create request with the same type as the service, ControlFinger
auto request = std::make_shared<hrim_actuator_gripper_srvs::srv::ControlFinger::Request>();

// Position range 0 - 0.87 rad
request->goal_linearposition = 0.87;
request->goal_angularposition = 0.;

// Wait for service to be avaiable before calling it
while (!client->wait_for_service(1s)) {
Expand Down
4 changes: 2 additions & 2 deletions gripper_minimal_service/src/gripper_minimal_client_v2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@ class MinimalClient : public rclcpp::Node
MinimalClient(): Node("gripper_minimal_client")
{
client = this->create_client<hrim_actuator_gripper_srvs::srv::ControlFinger>(
"/hrim_actuation_gripper_000000000004/goal");
"/hrim_actuator_gripper_000000000004/fingercontrol");

// Wait for service to be avaiable before calling it
while (!client->wait_for_service(1s)) {
Expand All @@ -29,7 +29,7 @@ class MinimalClient : public rclcpp::Node
};

void MinimalClient::send_request(){
request->goal_linearposition = 0.87;
request->goal_angularposition = 0.;;
this->future = client->async_send_request(request);
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@
node = rclpy.create_node("mara_minimal_publisher")

# Create a publisher on topic "/hrim_actuation_servomotor_000000000001/goal_axis1"
pub = node.create_publisher(GoalRotaryServo, '/hrim_actuation_servomotor_000000000001/goal_axis1', qos_profile=qos_profile_sensor_data)
pub = node.create_publisher(GoalRotaryServo, '/hrim_actuator_rotaryservo_000000000001/goal_axis1', qos_profile=qos_profile_sensor_data)

# Create message with the same type as the topic, GoalRotaryServo
msg = GoalRotaryServo()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ def __init__(self):
super().__init__('mara_minimal_publisher')

# Create a publisher on topic "/hrim_actuation_servomotor_000000000001/goal_axis1"
self.pub_ = self.create_publisher(GoalRotaryServo, '/hrim_actuation_servomotor_000000000001/goal_axis1',
self.pub_ = self.create_publisher(GoalRotaryServo, '/hrim_actuator_rotaryservo_000000000001/goal_axis1',
qos_profile=qos_profile_sensor_data)

# Create message with the same type as the topic, GoalRotaryServo
Expand Down
4 changes: 2 additions & 2 deletions mara_minimal_publisher/src/mara_minimal_publisher_v1.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@ int main(int argc, char * argv[])
auto node = rclcpp::Node::make_shared("mara_minimal_publisher");

// Create a publisher on topic "/hrim_actuation_servomotor_000000000001/goal_axis1"
auto pub = node->create_publisher<hrim_actuator_rotaryservo_msgs::msg::GoalRotaryServo>("/hrim_actuation_servomotor_000000000001/goal_axis1", rmw_qos_profile_sensor_data);
auto pub = node->create_publisher<hrim_actuator_rotaryservo_msgs::msg::GoalRotaryServo>("/hrim_actuator_rotaryservo_000000000001/goal_axis1", rclcpp::SensorDataQoS());

// Publishing rate of 1 Hz
rclcpp::WallRate loop_rate(1);
Expand All @@ -29,7 +29,7 @@ int main(int argc, char * argv[])
msg->control_type = 4; // Position and velocity control

// Publish message!
pub->publish(msg);
pub->publish(*msg);

// Spin not really needed here since we don't have callbacks
rclcpp::spin_some(node);
Expand Down
4 changes: 2 additions & 2 deletions mara_minimal_publisher/src/mara_minimal_publisher_v2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ class MinimalPublisher : public rclcpp::Node
count_(0)
{
// Create a publisher on topic "/hrim_actuation_servomotor_000000000001/goal_axis1"
pub_ = this->create_publisher<hrim_actuator_rotaryservo_msgs::msg::GoalRotaryServo>("/hrim_actuation_servomotor_000000000001/goal_axis1");
pub_ = this->create_publisher<hrim_actuator_rotaryservo_msgs::msg::GoalRotaryServo>("/hrim_actuator_rotaryservo_000000000001/goal_axis1", rclcpp::SensorDataQoS());

// Publishing rate of 1 Hz using a wall timer
timer_ = this->create_wall_timer(1s, std::bind(&MinimalPublisher::timer_callback, this));
Expand All @@ -30,7 +30,7 @@ class MinimalPublisher : public rclcpp::Node
msg->control_type = 4; // Position and velocity control

// Publish message!
pub_->publish(msg);
pub_->publish(*msg);

// Log
RCLCPP_INFO(this->get_logger(), "Iteration number %d", count_);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ def minimal_callback(msg):
node = rclpy.create_node('mara_minimal_subscriber')

# Subscribe to topic "/hrim_actuation_servomotor_000000000001/state_axis1" and link it to "minimal_callback" function
node.create_subscription(StateRotaryServo, '/hrim_actuation_servomotor_000000000001/state_axis1', minimal_callback,
node.create_subscription(StateRotaryServo, '/hrim_actuator_rotaryservo_000000000001/state_axis1', minimal_callback,
qos_profile=qos_profile_sensor_data) # QoS profile for reading (joint) sensors

# Spin listening to all subscribed topics
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ def __init__(self):
super().__init__('mara_minimal_subscriber')

# Subscribe to topic "/hrim_actuation_servomotor_000000000001/state_axis1" and link it to "minimal_callback" function
self.create_subscription(StateRotaryServo, '/hrim_actuation_servomotor_000000000001/state_axis1',
self.create_subscription(StateRotaryServo, '/hrim_actuator_rotaryservo_000000000001/state_axis1',
self.minimal_callback,
qos_profile=qos_profile_sensor_data) # QoS profile for reading (joint) sensors

Expand Down
6 changes: 3 additions & 3 deletions mara_minimal_subscriber/src/mara_minimal_subscriber_v1.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,9 +17,9 @@ int main(int argc, char * argv[])

// Subscribe to topic "/hrim_actuation_servomotor_000000000001/state_axis1" and link it to "minimal_callback" function
auto sub = node->create_subscription<hrim_actuator_rotaryservo_msgs::msg::StateRotaryServo>(
"/hrim_actuation_servomotor_000000000001/state_axis1",
minimal_callback,
rmw_qos_profile_sensor_data); // QoS profile for reading (joint) sensors
"/hrim_actuator_rotaryservo_000000000001/state_axis1",
rclcpp::SensorDataQoS(), // QoS profile for reading (joint) sensors
minimal_callback);

// Spin listening to all subscribed topics
rclcpp::spin(node);
Expand Down
6 changes: 3 additions & 3 deletions mara_minimal_subscriber/src/mara_minimal_subscriber_v2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,9 +9,9 @@ class MinimalSubscriber : public rclcpp::Node
MinimalSubscriber(): Node("minimal_subscriber")
{
sub_ = this->create_subscription<hrim_actuator_rotaryservo_msgs::msg::StateRotaryServo>(
"/hrim_actuation_servomotor_000000000001/state_axis1",
std::bind(&MinimalSubscriber::minimal_callback, this, _1),
rmw_qos_profile_sensor_data);
"/hrim_actuator_rotaryservo_000000000001/state_axis1",
rclcpp::SensorDataQoS(),
std::bind(&MinimalSubscriber::minimal_callback, this, _1));
}

private:
Expand Down
17 changes: 0 additions & 17 deletions mara_minimal_trajectory_action/README.md

This file was deleted.

Loading

0 comments on commit f635475

Please sign in to comment.