Skip to content

Commit

Permalink
Specifing Reference Components for each Publisher and Subscriber (#113)
Browse files Browse the repository at this point in the history
* Changing OdometrySubscriber to have a public Transform instead of a public GameObject; updating demo scene
* Changing LaserScanPublisher to have a public LaserScanReader instead of a public GameObject
* Adding public Transform to PoseStampedSubscriber,TwistSubscriber and TwistPublisher
* Cleanup and Formatting
  • Loading branch information
MartinBischoff authored Sep 5, 2018
1 parent b71fef4 commit 9725f10
Show file tree
Hide file tree
Showing 13 changed files with 60 additions and 57 deletions.
3 changes: 2 additions & 1 deletion Unity3D/Assets/RosSharp/Scenes/GazeboSimulationScene.unity
Original file line number Diff line number Diff line change
Expand Up @@ -13843,6 +13843,7 @@ MonoBehaviour:
m_Script: {fileID: 11500000, guid: 5f9b8f32224ca04498ffd0a2e2bc0567, type: 3}
m_Name:
m_EditorClassIdentifier:
timeout: 10
Protocol: 1
RosBridgeServerUrl: ws://192.168.56.102:9090
--- !u!4 &2016988257
Expand Down Expand Up @@ -13871,7 +13872,7 @@ MonoBehaviour:
m_EditorClassIdentifier:
Topic: /odom
TimeStep: 0
assignedObject: {fileID: 1740361386}
PublishedTransform: {fileID: 1740361389}
--- !u!114 &2016988259
MonoBehaviour:
m_ObjectHideFlags: 0
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,16 +16,14 @@ limitations under the License.
// Adjustments to new Publication Timing and Execution Framework
// © Siemens AG, 2018, Dr. Martin Bischoff ([email protected])

using System.Collections;
using UnityEngine;

namespace RosSharp.RosBridgeClient
{

public class ImagePublisher : Publisher<Messages.Sensor.CompressedImage>
{
public string FrameId = "Camera";
public Camera ImageCamera;
public string FrameId = "Camera";
public int resolutionWidth = 640;
public int resolutionHeight = 480;
[Range(0, 100)]
Expand All @@ -35,9 +33,6 @@ public class ImagePublisher : Publisher<Messages.Sensor.CompressedImage>
private Texture2D texture2D;
private Rect rect;

private float lastCommunicationTime;
public float MinTime;

protected override void Start()
{
base.Start();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,12 +20,11 @@ namespace RosSharp.RosBridgeClient
[RequireComponent(typeof(RosConnector))]
public class ImageSubscriber : Subscriber<Messages.Sensor.CompressedImage>
{
private byte[] imageData;
private bool isMessageReceived;

public MeshRenderer meshRenderer;
private Texture2D texture2D;

private Texture2D texture2D;
private byte[] imageData;
private bool isMessageReceived;

protected override void Start()
{
Expand All @@ -52,6 +51,7 @@ private void ProcessMessage()
meshRenderer.material.SetTexture("_MainTex", texture2D);
isMessageReceived = false;
}

}
}

Original file line number Diff line number Diff line change
Expand Up @@ -17,11 +17,11 @@ namespace RosSharp.RosBridgeClient
{
public class JointStatePublisher : Publisher<Messages.Sensor.JointState>
{
private Messages.Sensor.JointState message;
public string FrameId = "Unity";

public JointStateReader[] JointStateReaders;
public string FrameId = "Unity";

private Messages.Sensor.JointState message;

protected override void Start()
{
base.Start();
Expand All @@ -45,6 +45,7 @@ private void InitializeMessage()
effort = new float[jointStateLength]
};
}

private void UpdateMessage()
{
message.header.Update();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,12 +17,13 @@ namespace RosSharp.RosBridgeClient
{
public class JoyPublisher : Publisher<Messages.Sensor.Joy>
{
private Messages.Sensor.Joy message;
public string FrameId = "Unity";

private JoyAxisReader[] JoyAxisReaders;
private JoyButtonReader[] JoyButtonReaders;

public string FrameId = "Unity";

private Messages.Sensor.Joy message;

protected override void Start()
{
base.Start();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,15 +19,13 @@ namespace RosSharp.RosBridgeClient
{
public class LaserScanPublisher : Publisher<Messages.Sensor.LaserScan>
{
private Messages.Sensor.LaserScan message;
private LaserScanReader laserScanReader;
private float previousScanTime = 0;


public LaserScanReader laserScanReader;
public string FrameId = "Unity";
public GameObject LaserScannerObject;

private Messages.Sensor.LaserScan message;
private float scanPeriod;
private float previousScanTime = 0;

protected override void Start()
{
base.Start();
Expand All @@ -41,12 +39,10 @@ private void FixedUpdate()
UpdateMessage();
previousScanTime = Time.realtimeSinceStartup;
}

}

private void InitializeMessage()
{
laserScanReader = LaserScannerObject.GetComponent<LaserScanReader>();
scanPeriod = (float)laserScanReader.samples / (float)laserScanReader.update_rate;

message = new Messages.Sensor.LaserScan
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,9 +13,6 @@ You may obtain a copy of the License at
limitations under the License.
*/

using UnityEngine;
using System;

namespace RosSharp.RosBridgeClient
{
public class LaserScanSubscriber : Subscriber<Messages.Sensor.LaserScan>
Expand All @@ -31,6 +28,5 @@ protected override void ReceiveMessage(Messages.Sensor.LaserScan laserScan)
{
laserScanWriter.Write(laserScan);
}

}
}
Original file line number Diff line number Diff line change
Expand Up @@ -19,10 +19,11 @@ namespace RosSharp.RosBridgeClient
{
public class OdometrySubscriber : Subscriber<Messages.Navigation.Odometry>
{
public Transform PublishedTransform;

private Vector3 position;
private Quaternion rotation;
private bool isMessageReceived;
public GameObject assignedObject;

protected override void Start()
{
Expand All @@ -43,8 +44,8 @@ protected override void ReceiveMessage(Messages.Navigation.Odometry message)
}
private void ProcessMessage()
{
assignedObject.transform.position = position;
assignedObject.transform.rotation = rotation;
PublishedTransform.position = position;
PublishedTransform.rotation = rotation;
}

private Vector3 GetPosition(Messages.Navigation.Odometry message)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,9 +19,10 @@ namespace RosSharp.RosBridgeClient
{
public class PoseStampedPublisher : Publisher<Messages.Geometry.PoseStamped>
{
private Messages.Geometry.PoseStamped message;
public string FrameId = "Unity";
public Transform PublishedTransform;
public string FrameId = "Unity";

private Messages.Geometry.PoseStamped message;

protected override void Start()
{
Expand All @@ -31,14 +32,18 @@ protected override void Start()

private void FixedUpdate()
{
UpdateMessage();
UpdateMessage();
}

private void InitializeMessage()
{
message = new Messages.Geometry.PoseStamped();
message.header = new Messages.Standard.Header();
message.header.frame_id = FrameId;
message = new Messages.Geometry.PoseStamped
{
header = new Messages.Standard.Header()
{
frame_id = FrameId
}
};
}

private void UpdateMessage()
Expand Down Expand Up @@ -68,5 +73,6 @@ private Messages.Geometry.Quaternion GetGeometryQuaternion(Quaternion quaternion
geometryQuaternion.w = quaternion.w;
return geometryQuaternion;
}

}
}
Original file line number Diff line number Diff line change
Expand Up @@ -19,11 +19,13 @@ namespace RosSharp.RosBridgeClient
{
public class PoseStampedSubscriber : Subscriber<Messages.Geometry.PoseStamped>
{
public Transform PublishedTransform;

private Vector3 position;
private Quaternion rotation;
private bool isMessageReceived;

protected override void Start()
protected override void Start()
{
base.Start();
}
Expand All @@ -43,8 +45,8 @@ protected override void ReceiveMessage(Messages.Geometry.PoseStamped message)

private void ProcessMessage()
{
transform.position = position;
transform.rotation = rotation;
PublishedTransform.position = position;
PublishedTransform.rotation = rotation;
}

private Vector3 GetPosition(Messages.Geometry.PoseStamped message)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -72,5 +72,6 @@ private void OnClosed(object sender, EventArgs e)
{
Debug.Log("Disconnected from RosBridge: " + RosBridgeServerUrl);
}

}
}
Original file line number Diff line number Diff line change
Expand Up @@ -19,8 +19,9 @@ namespace RosSharp.RosBridgeClient
{
public class TwistPublisher : Publisher<Messages.Geometry.Twist>
{
private Messages.Geometry.Twist message;
public Transform PublishedTransform;

private Messages.Geometry.Twist message;
private float previousRealTime;
private Vector3 previousPosition = Vector3.zero;
private Quaternion previousRotation = Quaternion.identity;
Expand All @@ -46,15 +47,15 @@ private void UpdateMessage()
{
float deltaTime = Time.realtimeSinceStartup - previousRealTime;

Vector3 linearVelocity = (transform.position - previousPosition)/deltaTime;
Vector3 angularVelocity = (transform.rotation.eulerAngles - previousRotation.eulerAngles)/deltaTime;
Vector3 linearVelocity = (PublishedTransform.position - previousPosition)/deltaTime;
Vector3 angularVelocity = (PublishedTransform.rotation.eulerAngles - previousRotation.eulerAngles)/deltaTime;

message.linear = GetGeometryVector3(linearVelocity.Unity2Ros()); ;
message.angular = GetGeometryVector3(- angularVelocity.Unity2Ros());

previousRealTime = Time.realtimeSinceStartup;
previousPosition = transform.position;
previousRotation = transform.rotation;
previousPosition = PublishedTransform.position;
previousRotation = PublishedTransform.rotation;

Publish(message);
}
Expand Down
24 changes: 13 additions & 11 deletions Unity3D/Assets/RosSharp/Scripts/RosCommuncation/TwistSubscriber.cs
Original file line number Diff line number Diff line change
Expand Up @@ -22,15 +22,17 @@ namespace RosSharp.RosBridgeClient
{
public class TwistSubscriber : Subscriber<Messages.Geometry.Twist>
{
public Transform SubscribedTransform;

private float previousRealTime;
private Vector3 linearVelocity;
private Vector3 angularVelocity;
private bool isMessageReceived;

protected override void Start()
{
base.Start();
}
protected override void Start()
{
base.Start();
}

protected override void ReceiveMessage(Messages.Geometry.Twist message)
{
Expand All @@ -41,7 +43,7 @@ protected override void ReceiveMessage(Messages.Geometry.Twist message)

private static Vector3 ToVector3(Messages.Geometry.Vector3 geometryVector3)
{
return new Vector3(geometryVector3.x,geometryVector3.y,geometryVector3.z);
return new Vector3(geometryVector3.x, geometryVector3.y, geometryVector3.z);
}

private void Update()
Expand All @@ -51,16 +53,16 @@ private void Update()
}
private void ProcessMessage()
{
float deltaTime = Time.realtimeSinceStartup-previousRealTime;
float deltaTime = Time.realtimeSinceStartup - previousRealTime;

transform.Translate(linearVelocity * deltaTime);
transform.Rotate(Vector3.forward, angularVelocity.x * deltaTime);
transform.Rotate(Vector3.up, angularVelocity.y * deltaTime);
transform.Rotate(Vector3.left, angularVelocity.z * deltaTime);
SubscribedTransform.Translate(linearVelocity * deltaTime);
SubscribedTransform.Rotate(Vector3.forward, angularVelocity.x * deltaTime);
SubscribedTransform.Rotate(Vector3.up, angularVelocity.y * deltaTime);
SubscribedTransform.Rotate(Vector3.left, angularVelocity.z * deltaTime);

previousRealTime = Time.realtimeSinceStartup;

isMessageReceived = false;
}
}
}
}

0 comments on commit 9725f10

Please sign in to comment.